Module API¶
rocon_python_comms¶
This is the top-level namespace of the rocon_python_comms ROS package. It provides additional python modules beyond rospy for working with ros python communications.
rocon_python_comms.connections¶
This is a wrapper around the many ad-hoc modules that work with the ros master system state list of pubs, subs, services and actions. In some cases it just extends the functionality (severely lacking in some cases) and in others it provides new, higher level methods (e.g. for actions). —-
-
class
rocon_python_comms.connections.
Connection
(connection_type, name, node, type_msg=None, type_info=None, xmlrpc_uri=None)[source]¶ Bases:
object
An object that represents a connection containing all the gory details about a connection, allowing a connection to be passed along to other nodes.
Note, we use a ros msg type as a data structure for the variable storage. This lets users spin it off in the ros world as needed as well as providing extra operators for manipulation and handling of connection types on top.
-
__eq__
(other)[source]¶ Don’t need to check every characteristic of the connection to uniquely identify it, just the name, node and type.
-
__init__
(connection_type, name, node, type_msg=None, type_info=None, xmlrpc_uri=None)[source]¶ Parameters: - type (str) – type of connection from string constants in rocon_std_msgs.Connection (e.g. PUBLISHER)
- name (str) – the topic/service name or the action base name
- node (str) – the name of the node establishing this connection
- type_msg (str) – topic or service type, e.g. std_msgs/String
- type_info (str) – extra type information ( following rospy implementation ) : service uri or topic type
- xmlrpc_uri (str) – xmlrpc node uri for managing the connection
-
__weakref__
¶ list of weak references to the object (if defined)
-
generate_type_info_msg
()[source]¶ Basic connection details are provided by get system state from the master, which is a one shot call to give you information about every connection possible. it does not however provide type info information and the only way of retrieving that from the master is making one xmlrpc call to the master for every single connection. This gets expensive, so generating this information is usually delayed until we need it and done via this method.
-
-
class
rocon_python_comms.connections.
ConnectionCache
[source]¶ Bases:
object
Caches all of the connections living in a ros master. Use the ‘update’ method to force a refresh of the basic information for every connection.
-
__weakref__
¶ list of weak references to the object (if defined)
-
connections
= None¶ dict: dict structure of connections, by type.
-
find
(name)[source]¶ Convenience function for finding all connections with the specified name.
@TODO other find methods using a mix of name, node, type.
-
master
= None¶ rosgraph.Master: master API instance
-
update
(new_system_state=None, new_topic_types=None)[source]¶ Currently completely regenerating the connections dictionary and then taking diffs. Could be faster if we took diffs on the system state instead, but that’s a bit more awkward since each element has a variable list of nodes that we’d have to check against to get good diffs. e.g.
old_publishers = [‘/chatter’, [‘/talker’]] new_publishers = [‘/chatter’, [‘/talker’, ‘/babbler’]]
-
rocon_python_comms.exceptions¶
This module defines exceptions raised by the rocon_python_comms package. These exception names are all included in the main rocon_python_comms namespace. To catch one, import it this way:
from rocon_python_comms import ServicePairException
-
exception
rocon_python_comms.exceptions.
MultipleFoundException
[source]¶ Bases:
exceptions.IOError
Raised when a requested entity found multiple services, or didn’t return the correct result.
-
exception
rocon_python_comms.exceptions.
NotFoundException
[source]¶ Bases:
exceptions.IOError
Raised when a requested entity cannot be found, or didn’t return the correct result.
rocon_python_comms.nodes¶
This module contains anything relating to introspection or manipulation of ros nodes.
-
rocon_python_comms.nodes.
find_node
(wanted_node_name, unique=False)[source]¶ Do a lookup to find a node with the given name. The given name is treated as the unresolved node name. Hence this lookup will find nodes with the same name, but different namespaces.
This will raise exceptions, if the node couldn’t be found or in case unique is set multiple nodes with the same name are found.
Parameters: wanted_node_name (str) – unresolved name of the node looked for (e.g. ‘gateway’, not ‘/concert/gateway’) Returns: the fully resolved name of the node (unique) or list of fully resolved names (non-unique) Return type: str Raises: NotFoundException
Todo: accept resolved names -> https://github.com/robotics-in-concert/rocon_tools/issues/30 Todo: timeout -> https://github.com/robotics-in-concert/rocon_tools/issues/15
rocon_python_comms.service_pair_client¶
This module contains the client side api for communicating across a rocon service pair. A facade pattern is used here to simplify the interaction with the client side publisher and subscriber.
-
class
rocon_python_comms.service_pair_client.
ServicePairClient
(name, ServicePairSpec)[source]¶ Bases:
object
The client side of a pubsub service pair.This class provides a simplified api for handling requests/responses on the pubsub pair (client side). Although the development of this class was for non-blocking request-response behaviour, it does support legacy style blocking behavious as well.
Usage (Non-Blocking):
#!/usr/bin/env python import rospy from chatter.msg import ChatterRequest, ChatterResponse, ChatterPair from rocon_python_comms import ServicePairClient import unique_id class ChatterClient(object): def __init__(self): self.response = None self.client = ServicePairClient('chatter', ChatterPair) self.client.wait_for_service(rospy.Duration(3.0)) # should catch some exceptions here in case of timeouts self.request_id = self.client(ChatterRequest("Hello dude"), timeout=rospy.Duration(3.0), callback=self.callback) rospy.loginfo("Request id %s" % unique_id.toHexString(self.request_id)) if self.response is not None: print("Response %s" % self.response) def callback(self, request_id, msg): # ideally you'd check request_id against self.request_id self.response = msg rospy.loginfo("Got the response: %s" % msg) if __name__ == '__main__': rospy.init_node('chatter_client', anonymous=True) chatter_client = ChatterClient() rospy.spin()
Usage (Blocking):
#!/usr/bin/env python import rospy from chatter.msg import ChatterRequest, ChatterResponse, ChatterPair from rocon_python_comms import ServicePairClient import unique_id class ChatterClient(object): def __init__(self): self.response = None self.client = ServicePairClient('chatter', ChatterPair) self.client.wait_for_service(rospy.Duration(3.0)) # should catch some exceptions here in case of timeouts self.response = self.client(ChatterRequest("Hello dude"), timeout=rospy.Duration(3.0)) if self.response is not None: print("Response %s" % self.response) if __name__ == '__main__': rospy.init_node('chatter_client', anonymous=True) chatter_client = ChatterClient() rospy.spin()
-
ServicePairRequest
¶ Request msg type for this pair <ServicePairSpec>Request.
-
ServicePairResponse
¶ Response msg type for this pair <ServicePairSpec>Response.
-
ServicePairSpec
¶ Base message type for this pair.
-
__call__
(msg, timeout=None, callback=None, error_callback=None)[source]¶ Initiates and executes the client request to the server. The type of arguments supplied determines whether to apply blocking or non-blocking behaviour.
If no callback is supplied, the mode is blocking, otherwise non-blocking. If no timeout is specified, then a return of None indicates that the operation timed out.
Parameters: - msg (<name>Request) – the request message
- timeout (rospy.Duration) – time to wait for data
- callback (method with arguments (uuid_msgs.UniqueID, <name>Response)) – user callback invoked for responses of non-blocking calls
Returns: msg/id for blocking calls it is the response message, for non-blocking it is the unique id
Return type: <name>Response/uuid_msgs.UniqueID or None (if timed out)
-
wait_for_service
(timeout=None)[source]¶ Waits for the service pair server to appear. The input argument to timeout modifies the behaviour of this function as demonstrated below.
# one-shot if client.wait_for_service(): # do something useful # timeout if not client.wait_for_service(rospy.Duration(5.0)): rospy.logwarn("Timed out waiting for service to appear") # indefinite blocking client.wait_for_service(rospy.Duration(0))
Parameters: timeout (rospy.Duration) – time to wait for data Returns: bool true if connections found, false otherwise Raises: rospy.ROSInterruptException if shutdown interrupts wait
-
rocon_python_comms.service_pair_server¶
This module contains the server side api for communicating across a rocon service pair. A facade pattern is used here to simplify the interaction with the server side publisher and subscriber.
-
class
rocon_python_comms.service_pair_server.
ServicePairServer
(name, callback, ServicePairSpec, use_threads=False, queue_size=5)[source]¶ Bases:
object
The server side of a pubsub service pair. This class provides a simplified api for handling requests/responses on the pubsub pair. There are two modes of operation - 1) blocking and 2) threaded.
Non-Threaded
In the first, the users’ callback function directly runs whenever an incoming request is received. In this case, your callbacks should be very minimal so that incoming requests don’t get blocked and queued up.
#!/usr/bin/env python import rospy from chatter.msg import ChatterRequest, ChatterResponse, ChatterPair from rocon_python_comms import ServicePairServer class ChatterServer(object): def __init__(self): self.server = ServicePairServer('chatter', self.callback, ChatterPair) def callback(self, request_id, msg): rospy.loginfo("Server : I heard %s" % msg.babble) response = ChatterResponse() response.reply = "I heard %s" % msg.babble self.server.reply(request_id, response) if __name__ == '__main__': rospy.init_node('chatter_server', anonymous=True) chatter_server = ChatterServer() rospy.spin()
Threaded
In the second, we spawn a background thread and shunt the callback into this thread. Just toggle the
use_threads
flag when constructing the server:self.server = ServicePairServer('chatter', self.callback, ChatterPair, use_threads=True)
-
ServicePairRequest
¶ Request msg type for this pair <ServicePairSpec>Request.
-
ServicePairResponse
¶ Response msg type for this pair <ServicePairSpec>Response.
-
ServicePairSpec
¶ Base message type for this pair.
-
__init__
(name, callback, ServicePairSpec, use_threads=False, queue_size=5)[source]¶ Parameters: - name (str) – resource name of service pair (e.g. testies for pair topics testies/request, testies/response)
- callback – function invoked when a request arrives
- ServicePairSpec – the pair type (e.g. rocon_service_pair_msgs.msg.TestiesPair)
- use_threads (bool) – put the callback function into a fresh background thread when a request arrives.
- queue_size (int) – size of the queue to configure the publisher with.
-
reply
(request_id, msg)[source]¶ Send a reply to a previously received request (identified by request_id). Use this instead of writing directly to the publisher - just pass the content of the response data and the id that was issued with the request.
Parameters: - request_id (uuid_msgs.UniqueID) – the request id to associate with this response.
- msg (ServiceResponse) – the response
-
rocon_python_comms.services¶
This module contains anything relating to introspection or manipulation of ros services.
-
rocon_python_comms.services.
find_service
(service_type, timeout=rospy.Duration[5000000000], unique=False)[source]¶ Do a lookup to find services of the type specified. This will raise exceptions if it times out or returns multiple values. It can apply the additional logic of whether this should return a single unique result, or a list. Under the hood this calls out to the ros master for a list of registered services and it parses that to determine the result. If nothing is found, it loops around internally on a 10Hz loop until the result is found or the specified timeout is reached.
Warning
This api is particularly dangerous, especially if used across a wireless connection as it creates a socket connection to the master’s lookupService api for every service on the system while doing its hunting. More information in:
Usage:
from rocon_python_comms import find_service try: service_name = rocon_python_comms.find_service('rocon_interaction_msgs/SetInteractions', timeout=rospy.rostime.Duration(15.0), unique=True) except rocon_python_comms.NotFoundException as e: rospy.logwarn("failed to find the set_interactions service.")
Parameters: Returns: the fully resolved name of the service (unique) or list of names (non-unique)
Return type: Raises: Raises: rospy.ROSInterruptException
: if ros has shut down while searching.
rocon_python_comms.subscriber_proxy¶
This module provides a means of interacting with a ros latched publisher in the same style as you would a ros service (request-response).
-
class
rocon_python_comms.subscriber_proxy.
SubscriberProxy
(topic, msg_type)[source]¶ Works like a service proxy, but using a latched subscriber instead (regular subscribers will also work, but this is especially useful for latched subscribers since they typically always provide data).
If no timeout is specified when calling, it blocks indefinitely on a 100ms loop until a message arrives. Alternatively it will return with None if a specified timeout is reached.
Usage:
from rocon_python_comms import SubscriberProxy try: gateway_info = SubscriberProxy('gateway_info', gateway_msgs.GatewayInfo)(rospy.Duration(0.5)) if gateway_info is not None: # do something except rospy.exceptions.ROSInterruptException: # make sure to handle a Ros shutdown # react something
Todo: upgrade to make use of python events instead of manual loops -
__call__
(timeout=None)[source]¶ - Returns immediately with the latest data or blocks to a timeout/indefinitely until the next data arrives.
Parameters: timeout (rospy.Duration) – time to wait for data, polling at 10Hz (None = /infty) Returns: msg type data or None Return type: same as the msg type specified in the arg or None Returns: latest data or None
-
unregister
()[source]¶ Unregister the subscriber so future instantiations of this class can pull a fresh subscriber (important if the data is latched).
-
rocon_python_comms.topics¶
This module contains anything relating to introspection or manipulation of ros topics.
-
rocon_python_comms.topics.
find_topic
(topic_type, timeout=rospy.Duration[5000000000], unique=False)[source]¶ Do a lookup to find topics of the type specified. It can apply the additional logic of whether this should return a single unique result, or a list. Under the hood this calls out to the ros master for a list of registered topics and it parses that to determine the result. If nothing is found, it loops around internally on a 100ms loop until the result is found or the specified timeout is reached.
This will raise exceptions if it times out or returns multiple values.
Usage:
from rocon_python_comms import find_topic try: pairing_topic_name = find_topic('rocon_interaction_msgs/Pair', timeout=rospy.rostime.Duration(0.5), unique=True) except rocon_python_comms.NotFoundException as e: rospy.logwarn("support for interactions disabled")
Parameters: Returns: the fully resolved name of the topic (unique) or list of names (non-unique)
Return type: Raises: NotFoundException
if no topic is found within the timeout
rocon_python_comms.wall_rate¶
This module provides a wall time rate class (missing in rospy).