Package rospy :: Module client

Module client

source code

Additional ROS client API methods.

Functions
[str]
myargv(argv=None)
Remove ROS remapping arguments from sys.argv arguments.
source code
{str: val}
load_command_line_node_params(argv)
Load node param mappings (aka private parameters) encoded in command-line arguments, e.g.
source code
 
on_shutdown(h)
Register function to be called on shutdown.
source code
 
spin()
Blocks until ROS node is shutdown.
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
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, str]]
get_published_topics(namespace='/')
Retrieve list of topics that the master is reporting as being published.
source code
rospy.Message
wait_for_message(topic, topic_type, timeout=None)
Receive one message from topic.
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
 
set_param(param_name, param_value)
Set a parameter on the param server
source code
str
search_param(param_name)
Search for a parameter on the param server
source code
 
delete_param(param_name)
Delete a parameter on the param server
source code
 
has_param(param_name)
Test if parameter exists on the param server
source code
Variables
  TIMEOUT_READY = 15.0
  DEBUG = 1
  INFO = 2
  WARN = 4
  ERROR = 8
  FATAL = 16
  __package__ = 'rospy'
Function Details

myargv(argv=None)

source code 

Remove ROS remapping arguments from sys.argv arguments.

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

load_command_line_node_params(argv)

source code 

Load node param mappings (aka private parameters) encoded in command-line arguments, e.g. _foo:=bar. See also rosgraph.names.load_mappings.

Parameters:
  • argv - command-line arguments
  • argv - [str]
Returns: {str: val}
param->value remappings.

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.

spin()

source code 

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

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)

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_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]]

wait_for_message(topic, topic_type, timeout=None)

source code 

Receive one message from topic.

This will create a new subscription to the topic, receive one message, then unsubscribe.

Parameters:
  • topic (str) - name of topic
  • topic_type (rospy.Message class) - topic type
  • timeout (double|rospy.Duration) - timeout time in seconds or ROS Duration
Returns: rospy.Message
Message
Raises:

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:

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:

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:

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

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: