3. API 文档¶
此模块依赖 Robot Web Tools 所开发的 ROS bridge suite, 通过 WebSockets 实现与 ROS 的交互。
ROS bridge protocol 使用 JSON 格式信息传输 publishing, subscribing, service calls, actionlib, TF 等 ROS 中的功能。
3.1. ROS 设置¶
使用本模块,必须在 ROS 环境中配置并运行rosbridge
。
首次连接之前,在 ROS master所在环境用以下命令安装rosbridge suite:
sudo apt-get install -y ros-kinetic-rosbridge-server
sudo apt-get install -y ros-kinetic-tf2-web-republisher
在以后的每次连接之前,都要确保预先开启了以下服务:
roslaunch rosbridge_server rosbridge_websocket.launch
rosrun tf2_web_republisher tf2_web_republisher
注解
执行roslaunch
命令时,会自动运行roscore
命令,因此使用启动文件运行节点时不需要新开终端运行roscore
。
3.2. 连接 ROS¶
与 ROS 的连接是由Ros
类来处理的。除了连接和信息处理,在需要的时候它也会自动重连。
其他需要与 ROS 进行连接的类会将此实例作为其构造函数的参数接收。
-
class
roslibpy.
Ros
(host, port=None, is_secure=False)¶ Connection manager to ROS server.
-
call_in_thread
(callback)¶ Call the given function in a thread.
The threading implementation is deferred to the factory.
- Args:
- callback (
callable
): Callable function to be invoked.
-
call_later
(delay, callback)¶ Call the given function after a certain period of time has passed.
- Args:
- delay (
int
): Number of seconds to wait before invoking the callback. callback (callable
): Callable function to be invoked when ROS connection is ready.
-
close
()¶ Disconnect from ROS master.
-
connect
()¶ Connect to ROS master.
-
emit
(event_name, *args)¶ Trigger a named event.
-
get_action_servers
(callback, errback=None)¶ Retrieve list of action servers in ROS.
-
get_message_details
(message_type, callback, errback=None)¶ Retrieve details of a message type in ROS.
-
get_node_details
(node, callback, errback=None)¶ Retrieve list subscribed topics, publishing topics and services of a specific node name.
-
get_nodes
(callback, errback=None)¶ Retrieve list of active node names in ROS.
-
get_params
(callback, errback=None)¶ Retrieve list of param names from the ROS Parameter Server.
-
get_service_request_details
(type, callback, errback=None)¶ Retrieve details of a ROS Service Request.
-
get_service_response_details
(type, callback, errback=None)¶ Retrieve details of a ROS Service Response.
-
get_service_type
(service_name, callback, errback=None)¶ Retrieve the type of a service in ROS.
-
get_services
(callback, errback=None)¶ Retrieve list of active service names in ROS.
-
get_services_for_type
(service_type, callback, errback=None)¶ Retrieve list of services in ROS matching the specified type.
-
get_topic_type
(topic, callback, errback=None)¶ Retrieve the type of a topic in ROS.
-
get_topics
(callback, errback=None)¶ Retrieve list of topics in ROS.
-
get_topics_for_type
(topic_type, callback, errback=None)¶ Retrieve list of topics in ROS matching the specified type.
-
id_counter
¶ Generate an auto-incremental ID starting from 1.
- Returns:
- int: An auto-incremented ID.
-
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)¶ Remove a callback from an arbitrary named event.
- Args:
- event_name (
str
): Name of the event from which to unsubscribe. callback: Callable function. IfNone
, all callbacks of the event will be removed.
-
on
(event_name, callback)¶ Add a callback to an arbitrary named event.
- Args:
- 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)¶ Add a callback to be executed when the connection is established.
If a connection to ROS is already available, the callback is executed immediately.
- Args:
- 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=None)¶ Kick-starts a non-blocking event loop.
- Args:
- timeout: Timeout to wait until connection is ready.
-
run_forever
()¶ 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)¶ Send message to the ROS Master once the connection is established.
If a connection to ROS is already available, the message is sent immediately.
- Args:
- message (
Message
): ROS Bridge Message to send.
-
send_service_request
(message, callback, errback)¶ Send a service request to the ROS Master once the connection is established.
If a connection to ROS is already available, the request is sent immediately.
- Args:
- message (
Message
): ROS Bridge Message containing the request. callback: Callback invoked on successful execution. errback: Callback invoked on error.
-
terminate
()¶ Signals the termination of the main event loop.
-
3.3. ROS 主要概念¶
3.3.1. 话题¶
ROS 是一个通信框架。 在 ROS 里面, 不同的 节点 通过 messages 与其它节点通信。ROS messages 在Message
类中实现,并通过Topics
的发布/订阅模型来传输。
-
class
roslibpy.
Message
(values=None)¶ Message objects used for publishing and subscribing to/from topics.
A message is fundamentally a dictionary and behaves as one.
-
class
roslibpy.
Topic
(ros, name, message_type, compression=None, latch=False, throttle_rate=0, queue_size=100, queue_length=0)¶ Publish and/or subscribe to a topic in ROS.
- Args:
- 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.
-
advertise
()¶ Register as a publisher for the topic.
-
is_advertised
¶ Indicate if the topic is currently advertised or not.
- Returns:
- bool: True if advertised as publisher of this topic, False otherwise.
-
is_subscribed
¶ Indicate if the topic is currently subscribed or not.
- Returns:
- bool: True if subscribed to this topic, False otherwise.
-
publish
(message)¶ Publish a message to the topic.
- Args:
- message (
Message
): ROS Bridge Message to publish.
-
subscribe
(callback)¶ Register a subscription to the topic.
Every time a message is published for the given topic, the callback will be called with the message object.
- Args:
- callback: Function to be called when messages of this topic are published.
-
unadvertise
()¶ Unregister as a publisher for the topic.
-
unsubscribe
()¶ Unregister from a subscribed the topic.
3.3.2. 服务¶
除了话题的发布/订阅模型,ROS 还通过Services
类提供了一套请求/响应模型。
-
class
roslibpy.
Service
(ros, name, service_type)¶ 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.
- Args:
- 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)¶ 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.
- Args:
- 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)¶ Start a service call.
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.- Args:
- 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
.
-
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.
-
unadvertise
()¶ Unregister as a service server.
-
class
roslibpy.
ServiceRequest
(values=None)¶ Request for a service call.
-
class
roslibpy.
ServiceResponse
(values=None)¶ Response returned from a service call.
3.3.3. 参数服务器¶
ROS 提供了用于在不同节点之间分享数据的参数服务器。该服务通过Param
类来实现。
-
class
roslibpy.
Param
(ros, name)¶ A ROS parameter.
- Args:
- ros (
Ros
): Instance of the ROS connection. name (str
): Parameter name, e.g.max_vel_x
.
-
delete
(callback=None, errback=None)¶ Delete the parameter.
- Args:
- callback: Callable function to be invoked when the operation is completed. errback: Callback invoked on error.
-
get
(callback=None, errback=None)¶ Fetch the current value of the parameter.
- Args:
- callback: Callable function to be invoked when the operation is completed. errback: Callback invoked on error.
-
set
(value, callback=None, errback=None)¶ Set a new value to the parameter.
- Args:
- value: Value to set the parameter to. callback: Callable function to be invoked when the operation is completed. errback: Callback invoked on error.
3.4. Actionlib¶
另一个与 ROS 建立通讯的方法是通过 actionlib 栈。ROS 中的 Actions 允许执行可抢占任务,即可以被客户端中断的任务。
Actions 通过ActionClient
类来使用,它可以添加Goals
类。每个 goal 都可以发射出可侦听的事件,以便接收者对来自 Action 服务器的更新作出反应。可被发射的事件有四种:status,result,feedback 和 timeout。
-
class
roslibpy.actionlib.
Goal
(action_client, goal_message)¶ 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.
- Args:
- action_client (
ActionClient
): Instance of the action client associated with the goal. goal_message (Message
): Goal for the action server.
-
cancel
()¶ Cancel the current goal.
-
is_finished
¶ Indicate if the goal is finished or not.
- Returns:
- bool: True if finished, False otherwise.
-
send
(result_callback=None, timeout=None)¶ Send goal to the action server.
- Args:
- timeout (
int
): Timeout for the goal's result expressed in seconds. callback (callable
): Function to be called when a result is received. It is a shorthand for hooking on theresult
event.
-
wait
(timeout=None)¶ Block until the result is available.
If
timeout
isNone
, it will wait indefinitely.- Args:
- timeout (
int
): Timeout to wait for the result expressed in seconds. - Returns:
- Result of the goal.
-
class
roslibpy.actionlib.
ActionClient
(ros, server_name, action_name, timeout=None, omit_feedback=False, omit_status=False, omit_result=False)¶ Client to use ROS actions.
- Args:
- 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.
-
cancel
()¶ Cancel all goals associated with this action client.
-
dispose
()¶ Unsubscribe and unadvertise all topics associated with this action client.
-
class
roslibpy.actionlib.
SimpleActionServer
(ros, server_name, action_name)¶ 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.
- Args:
- 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
()¶ Indicate whether the client has requested preemption of the current goal.
-
send_feedback
(feedback)¶ Send feedback.
- Args:
- feedback (
dict
): Dictionary of key/values of the feedback message.
-
set_preempted
()¶ Set the current action to preempted (cancelled).
-
set_succeeded
(result)¶ Set the current action state to succeeded.
- Args:
- result (
dict
): Dictionary of key/values to set as the result of the action.
-
start
(action_callback)¶ Start the action server.
- Args:
- action_callback: Callable function to be invoked when a new goal is received. It takes one paramter containing the goal message.
-
class
roslibpy.actionlib.
GoalStatus
¶ Valid goal statuses.
3.5. TF¶
ROS 提供了一个非常强大的转换库,叫做 TF2,允许用户随时跟踪多个坐标系。
roslibpy 库通过TFClient
类与
tf2_web_republisher
连接来提供对它的访问。
-
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')¶ A TF Client that listens to TFs from tf2_web_republisher.
- Args:
- 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 to update the TF republisher's list of 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
.
-
dispose
()¶ Unsubscribe and unadvertise all topics associated with this instance.
-
subscribe
(frame_id, callback)¶ Subscribe to the given TF frame.
- Args:
- frame_id (
str
): TF frame identifier to subscribe to. callback (callable
): A callable functions receiving one parameter with transform data.
-
unsubscribe
(frame_id, callback)¶ Unsubscribe from the given TF frame.
- Args:
- frame_id (
str
): TF frame identifier to unsubscribe from. callback (callable
): The callback function to remove.
-
update_goal
()¶ Send a new service request to the tf2_web_republisher based on the current list of TFs.