gramaziokohler / roslibpy

Python ROS Bridge library
MIT License
280 stars 57 forks source link

Connection to ROS master #7

Closed MC-Bourguiba closed 6 years ago

MC-Bourguiba commented 6 years ago

Summary

I couldn't figure out a way to connect to ROS master without using run_forever. I need to call a service once it is triggered by an external agent and not having it planned before and the run_forever command blocks the process

Expected Result

True

Actual Result

False

Reproduction Steps

import roslibpy
ros = roslibpy.Ros(host='localhost', port=9090)
ros.connect()
ros.is_connected

System Information

Ubuntu , ROS kinetic, Python 3.6.

Thank you!

gonzalocasas commented 6 years ago

@MC-Bourguiba first of all, check the examples because you're not using the on_ready hook, so this wouldn't work in any case.

With that said, roslibpy in CPython (2.x or 3.x) uses Twisted reactors to handle the event loop. Calling run_forever simply the reactor for you. In general, that should be ok, because you'd normally want to setup the ROS connection, add some hooks and start the event loop with run_forever. Adding hooks means your code will execute at the right time (e.g. on_ready), while the main thread is blocked, and aborting the main thread means your program is exiting so you proceed to disconnect.

If you want to do something different or manage the event loop in a different way, you can, but Twisted is quite opinionated so you'd need to start using it more explicitly.

The following example starts the ROS connection in a separate thread and then uses the main thread for something else (in this case, just waiting, but you can add whatever in there):

import time
import roslibpy
import threading
from twisted.internet import reactor

def start_ros():
    ros = roslibpy.Ros('localhost', 9090)

    ros.on_ready(lambda: print('Is ROS connected?', ros.is_connected))

    reactor.run(installSignalHandlers=False)

t = threading.Thread(target=start_ros)
t.daemon = True
t.start()
print('Example is running...')

try:
    while True:
        time.sleep(1)
except KeyboardInterrupt:
    print('Ctrl+C detected, exiting...')

But there are some things to take into account:

We're considering moving away from Twisted and use ws4py instead, and use a threading connector instead of the event model of twisted. The only blocker for that right now is the consideration that ws4py is currently on hiatus and will not receive maintenance.

Hope this helps!

MC-Bourguiba commented 6 years ago

Thank you very much for your detailed answer! Unfortunately this does not fulfill the tasks that I want to do. To put you in the context, right now, I am using roslibjs and an API on python. Whenever a button is clicked on it will either call a service or the API and both interacts. I wanted to put everything in Python. An example of what I have is : `function Mode(){

var mode = document.getElementById("mode").value;
var setModeService = new ROSLIB.Service({
  ros : rosDrone.ros,
  name: '/mavros/set_mode',
  serviceType: 'mavros_msgs/SetMode'
});

var request = new ROSLIB.ServiceRequest({
  base_mode : 0,
  custom_mode : mode
});

setModeService.callService(request, function(result) {
  console.log(result);
});

}`

the rosDrone.ros is the equivalent of ros = roslibpy.Ros('localhost', 9090) but it instantiated once and then I can use it to call services listen to topics so on.. I will look deeper at the subject, thanks again!

gonzalocasas commented 6 years ago

@MC-Bourguiba roslibpy was designed to match roslibjs almost one to one, so, the same thing should work.

Here's a more or less complete example of the use case you mention, where there's input from the user (in this case coming from the console, but I assume you'll build a UI for that), and then calling ROS Services with the user input. I created an empty ros_drone object only to match the scenario you mention.

import roslibpy
import threading
from twisted.internet import reactor

try:
    input = raw_input
except NameError:
    pass

class RosDrone(object):
    pass

ros_drone = RosDrone()
ros_drone.ros = roslibpy.Ros('localhost', 9090)

# Start the reactor in a separate thread to avoid blocking main thread
t = threading.Thread(target=reactor.run, args=(False,))
t.daemon = True
t.start()

def change_mode(mode):
    set_mode_service = roslibpy.Service(
        ros=ros_drone.ros,
        name='/mavros/set_mode',
        service_type='mavros_msgs/SetMode')

    request = roslibpy.ServiceRequest({
        'base_mode': 0,
        'custom_mode': mode})

    set_mode_service.call(request, mode_changed, error_callback)

def mode_changed(result):
    print(result)

def error_callback(*args):
    print('Failed to change mode')

# Start the main UI loop
print('Starting...')

try:
    while True:
        mode = input('Change drone mode: ').lower().strip()

        if not ros_drone.ros.is_connected:
            print('ROS is not connected')
            continue

        change_mode(mode)
except KeyboardInterrupt:
    print('Ctrl+C detected, exiting...')

Cheers

MC-Bourguiba commented 6 years ago

works as a charm! thank you very much for your help and patience!