API Reference¶
This library relies on the ROS bridge suite by Robot Web Tools to interact with ROS via WebSockets.
The ROS bridge protocol uses JSON as message transport to allow access to ROS functionality such as publishing, subscribing, service calls, actionlib, TF, etc.
ROS Setup¶
In order to use this library, your ROS environment needs to be setup to run rosbridge
.
First install the rosbridge suite with the following commands:
sudo apt-get install -y ros-kinetic-rosbridge-server
sudo apt-get install -y ros-kinetic-tf2-web-republisher
And before starting a connection, make sure you launch all services:
roslaunch rosbridge_server rosbridge_websocket.launch
rosrun tf2_web_republisher tf2_web_republisher
Connecting to ROS¶
The connection to ROS is managed by the Ros
class. Besides connection and
disposal, it handles automatic reconnections when needed.
Other classes that need an active connection with ROS receive this instance as an argument to their constructors.
-
class
roslibpy.
Ros
(host, port=None, is_secure=False)[source]¶ Connection manager to ROS server.
- Parameters:
host (
str
) – Name or IP address of the ROS bridge host, e.g.127.0.0.1
.port (
int
) – ROS bridge port, e.g.9090
.is_secure (
bool
) –True
to use a secure web sockets connection, otherwiseFalse
.
-
blocking_call_from_thread
(callback, timeout)[source]¶ Call the given function from a thread, and wait for the result synchronously for as long as the timeout will allow.
- Parameters:
callback – Callable function to be invoked from the thread.
timeout (
int
) – Number of seconds to wait for the response before raising an exception.
- Returns:
The results from the callback, or a timeout exception.
-
call_async_service
(message, callback, errback)[source]¶ Send a service request to ROS once the connection is established.
If a connection to ROS is already available, the request is sent immediately.
- Parameters:
message (
Message
) – ROS Bridge Message containing the request.callback – Callback invoked on successful execution.
errback – Callback invoked on error.
-
call_in_thread
(callback)[source]¶ Call the given function in a thread.
The threading implementation is deferred to the factory.
- Parameters:
callback (
callable
) – Callable function to be invoked.
-
call_later
(delay, callback)[source]¶ Call the given function after a certain period of time has passed.
- Parameters:
delay (
int
) – Number of seconds to wait before invoking the callback.callback (
callable
) – Callable function to be invoked when ROS connection is ready.
-
call_sync_service
(message, timeout)[source]¶ Send a blocking service request to ROS once the connection is established, waiting for the result to be return.
If a connection to ROS is already available, the request is sent immediately.
- Parameters:
message (
Message
) – ROS Bridge Message containing the request.timeout (
int
) – Number of seconds to wait for the response before raising an exception.
- Returns:
Either returns the service request results or raises a timeout exception.
-
delete_param
(name, callback=None, errback=None)[source]¶ Delete parameter from the ROS Parameter Server.
Note
To make this a blocking call, pass
None
to thecallback
parameter .-
get_message_details
(message_type, callback=None, errback=None)[source]¶ Retrieve details of a message type in ROS.
Note
To make this a blocking call, pass
None
to thecallback
parameter .- Returns:
Message type details if blocking, otherwise
None
.
-
get_node_details
(node, callback=None, errback=None)[source]¶ Retrieve list subscribed topics, publishing topics and services of a specific node name.
Note
To make this a blocking call, pass
None
to thecallback
parameter .-
get_nodes
(callback=None, errback=None)[source]¶ Retrieve list of active node names in ROS.
Note
To make this a blocking call, pass
None
to thecallback
parameter .-
get_param
(name, callback=None, errback=None)[source]¶ Get the value of a parameter from the ROS Parameter Server.
Note
To make this a blocking call, pass
None
to thecallback
parameter .- Returns:
Parameter value if blocking, otherwise
None
.
-
get_params
(callback=None, errback=None)[source]¶ Retrieve list of param names from the ROS Parameter Server.
Note
To make this a blocking call, pass
None
to thecallback
parameter .- Returns:
list – List of parameters if blocking, otherwise
None
.
-
get_service_request_callback
(message)[source]¶ Get the callback which, when called, sends the service request.
- Parameters:
message (
Message
) – ROS Bridge Message containing the request.- Returns:
A callable which makes the service request.
-
get_service_request_details
(type, callback=None, errback=None)[source]¶ Retrieve details of a ROS Service Request.
Note
To make this a blocking call, pass
None
to thecallback
parameter .- Returns:
Service Request details if blocking, otherwise
None
.
-
get_service_response_details
(type, callback=None, errback=None)[source]¶ Retrieve details of a ROS Service Response.
Note
To make this a blocking call, pass
None
to thecallback
parameter .- Returns:
Service Response details if blocking, otherwise
None
.
-
get_service_type
(service_name, callback=None, errback=None)[source]¶ Retrieve the type of a service in ROS.
Note
To make this a blocking call, pass
None
to thecallback
parameter .- Returns:
str – Service type if blocking, otherwise
None
.
-
get_services
(callback=None, errback=None)[source]¶ Retrieve list of active service names in ROS.
Note
To make this a blocking call, pass
None
to thecallback
parameter .- Returns:
list – List of services if blocking, otherwise
None
.
-
get_services_for_type
(service_type, callback=None, errback=None)[source]¶ Retrieve list of services in ROS matching the specified type.
Note
To make this a blocking call, pass
None
to thecallback
parameter .- Returns:
list – List of services matching the specified type if blocking, otherwise
None
.
-
get_time
(callback=None, errback=None)[source]¶ Retrieve the current ROS time.
Note
To make this a blocking call, pass
None
to thecallback
parameter .- Returns:
Time
– An instance of ROS Time.
-
get_topic_type
(topic, callback=None, errback=None)[source]¶ Retrieve the type of a topic in ROS.
Note
To make this a blocking call, pass
None
to thecallback
parameter .- Returns:
str – Topic type if blocking, otherwise
None
.
-
get_topics
(callback=None, errback=None)[source]¶ Retrieve list of topics in ROS.
Note
To make this a blocking call, pass
None
to thecallback
parameter .- Returns:
list – List of topics if blocking, otherwise
None
.
-
get_topics_for_type
(topic_type, callback=None, errback=None)[source]¶ Retrieve list of topics in ROS matching the specified type.
Note
To make this a blocking call, pass
None
to thecallback
parameter .- Returns:
list – List of topics matching the specified type if blocking, otherwise
None
.
-
property
id_counter
¶ Generate an auto-incremental ID starting from 1.
- Returns:
int – An auto-incremented ID.
-
property
is_connected
¶ Indicate if the ROS connection is open or not.
- Returns:
bool – True if connected to ROS, False otherwise.
-
off
(event_name, callback=None)[source]¶ Remove a callback from an arbitrary named event.
- Parameters:
event_name (
str
) – Name of the event from which to unsubscribe.callback – Callable function. If
None
, all callbacks of the event will be removed.
-
on
(event_name, callback)[source]¶ Add a callback to an arbitrary named event.
- Parameters:
event_name (
str
) – Name of the event to which to subscribe.callback – Callable function to be executed when the event is triggered.
-
on_ready
(callback, run_in_thread=True)[source]¶ Add a callback to be executed when the connection is established.
If a connection to ROS is already available, the callback is executed immediately.
- Parameters:
callback – Callable function to be invoked when ROS connection is ready.
run_in_thread (
bool
) – True to run the callback in a separate thread, False otherwise.
-
run
(timeout=10)[source]¶ Kick-starts a non-blocking event loop.
- Parameters:
timeout – Timeout to wait until connection is ready.
-
run_forever
()[source]¶ Kick-starts a blocking loop to wait for events.
Depending on the implementations, and the client applications, running this might be required or not.
-
send_on_ready
(message)[source]¶ Send message to ROS once the connection is established.
If a connection to ROS is already available, the message is sent immediately.
- Parameters:
message (
Message
) – ROS Bridge Message to send.
-
set_param
(name, value, callback=None, errback=None)[source]¶ Set the value of a parameter from the ROS Parameter Server.
Note
To make this a blocking call, pass
None
to thecallback
parameter .-
roslibpy.
set_rosapi_timeout
(timeout)[source]¶ Set the default number of seconds to wait for a response before raising an exception.
- Parameters:
timeout (
int
) – Duration in seconds.
Main ROS concepts¶
Topics¶
ROS is a communication infrastructure. In ROS, different nodes communicate with each other through messages. ROS messages are represented by the
Message
class and are passed around viaTopics
using a publish/subscribe model.-
class
roslibpy.
Message
(values=None)[source]¶ Message objects used for publishing and subscribing to/from topics.
A message is fundamentally a dictionary and behaves as one.
-
class
roslibpy.
Header
(seq=None, stamp=None, frame_id=None)[source]¶ Represents a message header of the ROS type std_msgs/Header.
-
class
roslibpy.
Topic
(ros, name, message_type, compression=None, latch=False, throttle_rate=0, queue_size=100, queue_length=0, reconnect_on_close=True)[source]¶ Publish and/or subscribe to a topic in ROS.
- Parameters:
ros (
Ros
) – Instance of the ROS connection.name (
str
) – Topic name, e.g./cmd_vel
.message_type (
str
) – Message type, e.g.std_msgs/String
.compression (
str
) – Type of compression to use, e.g. png. Defaults to None.throttle_rate (
int
) – Rate (in ms between messages) at which to throttle the topics.queue_size (
int
) – Queue size created at bridge side for re-publishing webtopics.latch (
bool
) – True to latch the topic when publishing, False otherwise.queue_length (
int
) – Queue length at bridge side used when subscribing.reconnect_on_close (
bool
) – Reconnect topic (both publisher & subscriber) on reconnection.
-
property
is_advertised
¶ Indicate if the topic is currently advertised or not.
- Returns:
bool – True if advertised as publisher of this topic, False otherwise.
-
property
is_subscribed
¶ Indicate if the topic is currently subscribed or not.
- Returns:
bool – True if subscribed to this topic, False otherwise.
-
publish
(message)[source]¶ Publish a message to the topic.
- Parameters:
message (
Message
) – ROS Bridge Message to publish.
Services¶
Besides the publish/subscribe model used with topics, ROS offers a request/response model via
Services
.-
class
roslibpy.
Service
(ros, name, service_type, reconnect_on_close=True)[source]¶ Client/server of ROS services.
This class can be used both to consume other ROS services as a client, or to provide ROS services as a server.
- Parameters:
ros (
Ros
) – Instance of the ROS connection.name (
str
) – Service name, e.g./add_two_ints
.service_type (
str
) – Service type, e.g.rospy_tutorials/AddTwoInts
.
-
advertise
(callback)[source]¶ Start advertising the service.
This turns the instance from a client into a server. The callback will be invoked with every request that is made to the service.
If the service is already advertised, this call does nothing.
- Parameters:
callback – Callback invoked on every service call. It should accept two parameters: service_request and service_response. It should return True if executed correctly, otherwise False.
-
call
(request, callback=None, errback=None, timeout=None)[source]¶ Start a service call.
Note
The service can be used either as blocking or non-blocking. If the
callback
parameter isNone
, then the call will block until receiving a response. Otherwise, the service response will be returned in the callback.- Parameters:
request (
ServiceRequest
) – Service request.callback – Callback invoked on successful execution.
errback – Callback invoked on error.
timeout – Timeout for the operation, in seconds. Only used if blocking.
- Returns:
object – Service response if used as a blocking call, otherwise
None
.
-
property
is_advertised
¶ Service servers are registered as advertised on ROS.
This class can be used to be a service client or a server.
- Returns:
bool – True if this is a server, False otherwise.
Parameter server¶
ROS provides a parameter server to share data among different nodes. This service can be accessed via the
Param
class.-
class
roslibpy.
Param
(ros, name)[source]¶ A ROS parameter.
- Parameters:
ros (
Ros
) – Instance of the ROS connection.name (
str
) – Parameter name, e.g.max_vel_x
.
-
delete
(callback=None, errback=None, timeout=None)[source]¶ Delete the parameter.
Note
This method can be used either as blocking or non-blocking. If the
callback
parameter isNone
, the call will block until completion.- Parameters:
callback – Callable function to be invoked when the operation is completed.
errback – Callback invoked on error.
timeout – Timeout for the operation, in seconds. Only used if blocking.
-
get
(callback=None, errback=None, timeout=None)[source]¶ Fetch the current value of the parameter.
Note
This method can be used either as blocking or non-blocking. If the
callback
parameter isNone
, the call will block and return the parameter value. Otherwise, the parameter value will be passed on to the callback.- Parameters:
callback – Callable function to be invoked when the operation is completed.
errback – Callback invoked on error.
timeout – Timeout for the operation, in seconds. Only used if blocking.
- Returns:
object – Parameter value if used as a blocking call, otherwise
None
.
-
set
(value, callback=None, errback=None, timeout=None)[source]¶ Set a new value to the parameter.
Note
This method can be used either as blocking or non-blocking. If the
callback
parameter isNone
, the call will block until completion.- Parameters:
callback – Callable function to be invoked when the operation is completed.
errback – Callback invoked on error.
timeout – Timeout for the operation, in seconds. Only used if blocking.
Time¶
To represent time, there is the concept of ROS time primitive type, which consists of two integers: seconds since epoch and nanoseconds since seconds.
-
class
roslibpy.
Time
(secs, nsecs)[source]¶ Represents ROS time with two integers: seconds since epoch and nanoseconds since seconds.
-
static
from_sec
(float_secs)[source]¶ Create new Time instance from a float seconds representation (e.g.
time.time()
).
-
property
nsecs
¶ Nanoseconds since seconds.
-
property
secs
¶ Seconds since epoch.
-
static
Actionlib¶
Another way to interact with ROS is through the actionlib stack. Actions in ROS allow to execute preemptable tasks, i.e. tasks that can be interrupted by the client.
Actions are used via the
ActionClient
to whichGoals
can be added. Each goal emits events that can be listened to in order to react to the updates from the action server. There are four events emmitted: status, result, feedback, and timeout.-
class
roslibpy.actionlib.
Goal
(action_client, goal_message)[source]¶ Goal for an action server.
After an event has been added to an action client, it will emit different events to indicate its progress:
status
: fires to notify clients on the current state of the goal.feedback
: fires to send clients periodic auxiliary information of the goal.result
: fires to send clients the result upon completion of the goal.timeout
: fires when the goal did not complete in the specified timeout window.
- Parameters:
action_client (
ActionClient
) – Instance of the action client associated with the goal.goal_message (
Message
) – Goal for the action server.
-
property
is_finished
¶ Indicate if the goal is finished or not.
- Returns:
bool – True if finished, False otherwise.
-
class
roslibpy.actionlib.
ActionClient
(ros, server_name, action_name, timeout=None, omit_feedback=False, omit_status=False, omit_result=False)[source]¶ Client to use ROS actions.
- Parameters:
ros (
Ros
) – Instance of the ROS connection.server_name (
str
) – Action server name, e.g./fibonacci
.action_name (
str
) – Action message name, e.g.actionlib_tutorials/FibonacciAction
.timeout (
int
) – Deprecated. Connection timeout, expressed in seconds.
-
class
roslibpy.actionlib.
SimpleActionServer
(ros, server_name, action_name)[source]¶ Implementation of the simple action server.
The server emits the following events:
goal
: fires when a new goal has been received by the server.cancel
: fires when the client has requested the cancellation of the action.
- Parameters:
ros (
Ros
) – Instance of the ROS connection.server_name (
str
) – Action server name, e.g./fibonacci
.action_name (
str
) – Action message name, e.g.actionlib_tutorials/FibonacciAction
.
-
is_preempt_requested
()[source]¶ Indicate whether the client has requested preemption of the current goal.
-
send_feedback
(feedback)[source]¶ Send feedback.
- Parameters:
feedback (
dict
) – Dictionary of key/values of the feedback message.
TF¶
ROS provides a very powerful transform library called TF2, which lets the user keep track of multiple coordinate frames over time.
The roslibpy library offers access to it through the tf2_web_republisher via the
TFClient
class.-
class
roslibpy.tf.
TFClient
(ros, fixed_frame='/base_link', angular_threshold=2.0, translation_threshold=0.01, rate=10.0, update_delay=50, topic_timeout=2000.0, server_name='/tf2_web_republisher', repub_service_name='/republish_tfs')[source]¶ A TF Client that listens to TFs from tf2_web_republisher.
- Parameters:
ros (
Ros
) – Instance of the ROS connection.fixed_frame (
str
) – Fixed frame, e.g./base_link
.angular_threshold (
float
) – Angular threshold for the TF republisher.translation_threshold (
float
) – Translation threshold for the TF republisher.rate (
float
) – Rate for the TF republisher.update_delay (
int
) – Time expressed in milliseconds to wait after a new subscription before update TFs.topic_timeout (
int
) – Timeout parameter for the TF republisher expressed in milliseconds.repub_service_name (
str
) – Name of the republish tfs service, e.g./republish_tfs
.
-
subscribe
(frame_id, callback)[source]¶ Subscribe to the given TF frame.
- Parameters:
frame_id (
str
) – TF frame identifier to subscribe to.callback (
callable
) – A callable functions receiving one parameter with transform data.
-
-
-
-