Package rospy

Package rospy

source code

ROS client library for Python. See http://ros.org/wiki/rospy


Author: Ken Conley (kwc)

Submodules

Classes
  AnyMsg
Message class to use for subscribing to any topic regardless of type.
  Duration
Duration represents the ROS 'duration' primitive type, which consists of two integers: seconds and nanoseconds.
  Header
  MasterProxy
Convenience wrapper for ROS master API and XML-RPC implementation.
  Message
Base class of Message data classes auto-generated from msg files.
  Publisher
Class for registering as a publisher of a ROS topic.
  ROSException
Base exception class for ROS clients
  ROSInitException
Exception for errors initializing ROS state
  ROSInternalException
Base class for exceptions that are internal to the ROS system
  ROSInterruptException
Exception for operations that interrupted, e.g.
  ROSSerializationException
Exception for message serialization errors
  Rate
Convenience class for sleeping in a loop at a specified rate
  Service
Declare a ROS service.
  ServiceException
Exception class for service-related errors
  ServiceProxy
Create a handle to a ROS service for invoking calls.
  SubscribeListener
Callback API to receive notifications when new subscribers connect and disconnect.
  Subscriber
Class for registering as a subscriber to a specified topic, where the messages are of a given type.
  Time
Time represents the ROS 'time' primitive type, which consists of two integers: seconds since epoch and nanoseconds since seconds.
  TransportException
Base class for transport-related exceptions
  TransportInitError
Internal exception for representing exceptions that occur establishing transports
  TransportTerminated
Internal class for representing broken connections
Functions
 
delete_param(param_name)
Delete a parameter on the param server
source code
str
get_caller_id()
Get fully resolved name of local node.
source code
rospy.MasterProxy
get_master(env={'LANG': 'en_US.UTF-8', 'ROS_DISTRO': 'melodic', 'PYTHONPATH':...)
Get a remote handle to the ROS Master.
source code
str
get_name()
Get fully resolved name of local node.
source code
str
get_namespace()
Get namespace of local node.
source code
str
get_node_uri()
Get this Node's URI.
source code
XmlRpcLegalValue
get_param(param_name, default=<rospy.client._Unspecified object>)
Retrieve a parameter from the param server
source code
XmlRpcLegalValue
get_param_cached(param_name, default=<rospy.client._Unspecified object>)
Retrieve a parameter from the param server with local caching
source code
[str]
get_param_names()
Retrieve list of parameter names.
source code
[[str, str]]
get_published_topics(namespace='/')
Retrieve list of topics that the master is reporting as being published.
source code
str
get_ros_root(*args, **kwargs)
Get the value of ROS_ROOT.
source code
Time
get_rostime()
Get the current time as a Time object
source code
float
get_time()
Get the current time as float secs (time.time() format)
source code
 
has_param(param_name)
Test if parameter exists on the param server
source code
 
init_node(name, argv=None, anonymous=False, log_level=None, disable_rostime=False, disable_rosout=False, disable_signals=False, xmlrpc_port=0, tcpros_port=0)
Register client node with the master under the specified name.
source code
bool
is_shutdown()
Returns: True if shutdown flag has been set
source code
 
logdebug(msg, *args, **kwargs) source code
 
logdebug_once(msg, *args, **kwargs) source code
 
logdebug_throttle(period, msg, *args, **kwargs) source code
 
logerr(msg, *args, **kwargs) source code
 
logerr_once(msg, *args, **kwargs) source code
 
logerr_throttle(period, msg, *args, **kwargs) source code
 
logfatal(msg, *args, **kwargs) source code
 
logfatal_once(msg, *args, **kwargs) source code
 
logfatal_throttle(period, msg, *args, **kwargs) source code
 
loginfo(msg, *args, **kwargs) source code
 
loginfo_once(msg, *args, **kwargs) source code
 
loginfo_throttle(period, msg, *args, **kwargs) source code
 
logout(msg, *args, **kwargs) source code
 
logwarn(msg, *args, **kwargs) source code
 
logwarn_once(msg, *args, **kwargs) source code
 
logwarn_throttle(period, msg, *args, **kwargs) source code
[str]
myargv(argv=None)
Remove ROS remapping arguments from sys.argv arguments.
source code
 
on_shutdown(h)
Register function to be called on shutdown.
source code
(str, int)
parse_rosrpc_uri(uri)
utility function for parsing ROS-RPC URIs
source code
str
remap_name(name, caller_id=None, resolved=True)
Remap a ROS name.
source code
str
resolve_name(name, caller_id=None)
Resolve a ROS name to its global, canonical form.
source code
str
search_param(param_name)
Search for a parameter on the param server
source code
 
set_param(param_name, param_value)
Set a parameter on the param server
source code
 
signal_shutdown(reason)
Initiates shutdown process by signaling objects waiting on _shutdown_lock.
source code
 
sleep(duration)
sleep for the specified duration in ROS time.
source code
 
spin()
Blocks until ROS node is shutdown.
source code
 
wait_for_service(service, timeout=None)
Blocks until service is available.
source code
Variables
  DEBUG = 1
  ERROR = 8
  FATAL = 16
  INFO = 2
  WARN = 4
Function Details

delete_param(param_name)

source code 

Delete a parameter on the param server

NOTE: this method is thread-safe.

Parameters:
  • param_name (str) - parameter name
Raises:
  • KeyError - if parameter is not set
  • ROSException - if parameter server reports an error

get_caller_id()

source code 

Get fully resolved name of local node. If this is not a node, use empty string

Returns: str
fully-qualified name of local node or '' if not applicable

get_master(env={'LANG': 'en_US.UTF-8', 'ROS_DISTRO': 'melodic', 'PYTHONPATH':...)

source code 

Get a remote handle to the ROS Master. This method can be called independent of running a ROS node, though the ROS_MASTER_URI must be declared in the environment.

Returns: rospy.MasterProxy
ROS Master remote object
Raises:
  • Exception - if server cannot be located or system cannot be initialized

get_name()

source code 

Get fully resolved name of local node. If this is not a node, use empty string

Returns: str
fully-qualified name of local node or '' if not applicable

get_namespace()

source code 

Get namespace of local node.

Returns: str
fully-qualified name of local node or '' if not applicable

get_node_uri()

source code 

Get this Node's URI.

Returns: str
this Node's XMLRPC URI

get_param(param_name, default=<rospy.client._Unspecified object>)

source code 

Retrieve a parameter from the param server

NOTE: this method is thread-safe.

Parameters:
  • default (any) - (optional) default value to return if key is not set
Returns: XmlRpcLegalValue
parameter value
Raises:
  • ROSException - if parameter server reports an error
  • KeyError - if value not set and default is not given

get_param_cached(param_name, default=<rospy.client._Unspecified object>)

source code 

Retrieve a parameter from the param server with local caching

NOTE: this method is thread-safe.

Parameters:
  • default (any) - (optional) default value to return if key is not set
Returns: XmlRpcLegalValue
parameter value
Raises:
  • ROSException - if parameter server reports an error
  • KeyError - if value not set and default is not given

get_param_names()

source code 

Retrieve list of parameter names.

NOTE: this method is thread-safe.

Returns: [str]
parameter names
Raises:

get_published_topics(namespace='/')

source code 

Retrieve list of topics that the master is reporting as being published.

Returns: [[str, str]]
List of topic names and types: [[topic1, type1]...[topicN, typeN]]

get_ros_root(*args, **kwargs)

source code 

Get the value of ROS_ROOT.

Parameters:
  • env (dict) - override environment dictionary
  • required - if True, fails with ROSException
Returns: str
Value of ROS_ROOT environment
Decorators:
  • @deprecated
Raises:

get_rostime()

source code 

Get the current time as a Time object

Returns: Time
current time as a rospy.Time object

get_time()

source code 

Get the current time as float secs (time.time() format)

Returns: float
time in secs (time.time() format)

has_param(param_name)

source code 

Test if parameter exists on the param server

NOTE: this method is thread-safe.

Parameters:
  • param_name (str) - parameter name
Raises:

init_node(name, argv=None, anonymous=False, log_level=None, disable_rostime=False, disable_rosout=False, disable_signals=False, xmlrpc_port=0, tcpros_port=0)

source code 

Register client node with the master under the specified name. This MUST be called from the main Python thread unless disable_signals is set to True. Duplicate calls to init_node are only allowed if the arguments are identical as the side-effects of this method are not reversible.

Parameters:
  • name (str) - Node's name. This parameter must be a base name, meaning that it cannot contain namespaces (i.e. '/')
  • argv ([str]) - Command line arguments to this program, including remapping arguments (default: sys.argv). If you provide argv to init_node(), any previously created rospy data structure (Publisher, Subscriber, Service) will have invalid mappings. It is important that you call init_node() first if you wish to provide your own argv.
  • anonymous (bool) - if True, a name will be auto-generated for the node using name as the base. This is useful when you wish to have multiple instances of the same node and don't care about their actual names (e.g. tools, guis). name will be used as the stem of the auto-generated name. NOTE: you cannot remap the name of an anonymous node.
  • log_level (int) - log level for sending message to /rosout and log file, which is INFO by default. For convenience, you may use rospy.DEBUG, rospy.INFO, rospy.ERROR, rospy.WARN, rospy.FATAL
  • disable_signals (bool) - If True, rospy will not register its own signal handlers. You must set this flag if (a) you are unable to call init_node from the main thread and/or you are using rospy in an environment where you need to control your own signal handling (e.g. WX). If you set this to True, you should call rospy.signal_shutdown(reason) to initiate clean shutdown.

    NOTE: disable_signals is overridden to True if roslib.is_interactive() is True.

  • disable_rostime (bool) - for internal testing only: suppresses automatic subscription to rostime
  • disable_rosout - for internal testing only: suppress auto-publication of rosout
  • xmlrpc_port (int) - If provided, it will use this port number for the client XMLRPC node.
  • tcpros_port (int) - If provided, the TCPROS server will listen for connections on this port
Raises:
  • ROSInitException - if initialization/registration fails
  • ValueError - if parameters are invalid (e.g. name contains a namespace or is otherwise illegal)

is_shutdown()

source code 
Returns: bool
True if shutdown flag has been set

myargv(argv=None)

source code 

Remove ROS remapping arguments from sys.argv arguments.

Returns: [str]
copy of sys.argv with ROS remapping arguments removed

on_shutdown(h)

source code 

Register function to be called on shutdown. This function will be called before Node begins teardown.

Parameters:
  • h (fn()) - Function with zero args to be called on shutdown.

parse_rosrpc_uri(uri)

source code 

utility function for parsing ROS-RPC URIs

Parameters:
  • uri (str) - ROSRPC URI
Returns: (str, int)
address, port
Raises:

remap_name(name, caller_id=None, resolved=True)

source code 

Remap a ROS name. This API should be used to instead of resolve_name for APIs in which you don't wish to resolve the name unless it is remapped.

Parameters:
  • name (str) - name to remap
  • resolved (bool) - if True (default), use resolved names in remappings, which is the standard for ROS.
Returns: str
Remapped name

resolve_name(name, caller_id=None)

source code 

Resolve a ROS name to its global, canonical form. Private ~names are resolved relative to the node name.

Parameters:
  • name (str) - name to resolve.
  • caller_id (str) - node name to resolve relative to. To resolve to local namespace, omit this parameter (or use None)
Returns: str
Resolved name. If name is empty/None, resolve_name returns parent namespace. If namespace is empty/None,

search_param(param_name)

source code 

Search for a parameter on the param server

NOTE: this method is thread-safe.

Parameters:
  • param_name (str) - parameter name
Returns: str
key of matching parameter or None if no matching parameter.
Raises:

set_param(param_name, param_value)

source code 

Set a parameter on the param server

NOTE: this method is thread-safe. If param_value is a dictionary it will be treated as a parameter tree, where param_name is the namespace. For example::

 {'x':1,'y':2,'sub':{'z':3}}

will set param_name/x=1, param_name/y=2, and param_name/sub/z=3. Furthermore, it will replace all existing parameters in the param_name namespace with the parameters in param_value. You must set parameters individually if you wish to perform a union update.

Parameters:
  • param_name (str) - parameter name
  • param_value (XmlRpcLegalValue) - parameter value
Raises:

signal_shutdown(reason)

source code 

Initiates shutdown process by signaling objects waiting on _shutdown_lock. Shutdown and pre-shutdown hooks are invoked.

Parameters:
  • reason (str) - human-readable shutdown reason, if applicable

sleep(duration)

source code 

sleep for the specified duration in ROS time. If duration is negative, sleep immediately returns.

Parameters:
  • duration (float or Duration) - seconds (or rospy.Duration) to sleep
Raises:

spin()

source code 

Blocks until ROS node is shutdown. Yields activity to other threads.

Raises:

wait_for_service(service, timeout=None)

source code 

Blocks until service is available. Use this in initialization code if your program depends on a service already running.

Parameters:
  • service (str) - name of service
  • timeout (double|rospy.Duration @note roscpp waitForService() has timeout specified in millisecs.) - timeout time in seconds or Duration, None for no timeout. NOTE: timeout=0 is invalid as wait_for_service actually contacts the service, so non-blocking behavior is not possible. For timeout=0 uses cases, just call the service without waiting.
Raises: