rosros 0.2.5
Simple unified interface to ROS1 / ROS2 Python API
Loading...
Searching...
No Matches
rosros.rospify.client Namespace Reference

Stand-ins for `rospy.client` in ROS2. More...

Classes

class  _unspecified
 

Functions

 delete_param (param_name)
 Deletes a parameter on the node.
 
 get_master (env=None)
 Returns a partial stand-in of `rospy.MasterProxy`.
 
 get_param (param_name, default=_unspecified)
 Returns a parameter value from the node.
 
 get_param_names ()
 Returns a list of node parameter names, with absolute namespace.
 
 get_published_topics (namespace="/")
 Returns a list of published topics.
 
 has_param (param_name)
 Test if parameter exists on the node.
 
 init_node (name, argv=None, anonymous=False, log_level=None, disable_rostime=None, disable_rosout=False, disable_signals=None, xmlrpc_port=None, tcpros_port=None)
 Inits ROS2 and creates ROS2 node.
 
 myargv (argv=None)
 Returns command-line arguments with remappings removed.
 
 on_shutdown (h)
 Registers function to be called on shutdown, after node has been torn down.
 
 search_param (param_name)
 Search for a parameter on the node.
 
 set_param (param_name, param_value)
 Set a parameter on the node.
 
 spin ()
 Spins ROS2 node forever.
 
 wait_for_message (topic, topic_type, timeout=None)
 Receive one message from topic.
 

Variables

dict _ROSPY_LOG_LEVEL_TO_PY_LEVEL
 Map rospy log level constants to Python logging level constants.
 
int DEBUG = 1
 
int ERROR = 8
 
int FATAL = 16
 
 get_param_cached = get_param
 Stand-in for `rospy.get_param_cached`.
 
int INFO = 2
 
int WARN = 4
 

Detailed Description

Stand-ins for `rospy.client` in ROS2.

Function Documentation

◆ delete_param()

rosros.rospify.client.delete_param (   param_name)

Deletes a parameter on the node.

Parameters
param_nameparameter name

Definition at line 60 of file client.py.

◆ get_master()

rosros.rospify.client.get_master (   env = None)

Returns a partial stand-in of `rospy.MasterProxy`.

Parameters
envignored (ROS1 compatbility stand-in)

Definition at line 78 of file client.py.

◆ get_param()

rosros.rospify.client.get_param (   param_name,
  default = _unspecified 
)

Returns a parameter value from the node.

Parameters
defaultdefault value to return if key is not set
Returns
parameter value
Exceptions
KeyErrorif value not set and default is not given

Definition at line 89 of file client.py.

◆ get_param_names()

rosros.rospify.client.get_param_names ( )

Returns a list of node parameter names, with absolute namespace.

Definition at line 99 of file client.py.

◆ get_published_topics()

rosros.rospify.client.get_published_topics (   namespace = "/")

Returns a list of published topics.

Returns
list of topic and type names, as [[topic, type], ]
Exceptions
ROSExceptionif retrieving topics fails

Definition at line 112 of file client.py.

◆ has_param()

rosros.rospify.client.has_param (   param_name)

Test if parameter exists on the node.

Parameters
param_nameparameter name

Definition at line 69 of file client.py.

◆ init_node()

rosros.rospify.client.init_node (   name,
  argv = None,
  anonymous = False,
  log_level = None,
  disable_rostime = None,
  disable_rosout = False,
  disable_signals = None,
  xmlrpc_port = None,
  tcpros_port = None 
)

Inits ROS2 and creates ROS2 node.

Parameters
namenode name, with no namespace
argvlist of command-line arguments for the node
anonymouswhether to auto-generate a unique name for the node, using the given name as base
log_levellog level to set for the node logger, one of `rospify.DEBUG .INFO .WARN .ERROR .FATAL`
disable_rostimeignored (ROS1 compatibility stand-in)
disable_rosoutwhether to suppress auto-publication of rosout
disable_signalsignored (ROS1 compatibility stand-in)
xmlrpc_portignored (ROS1 compatibility stand-in)
tcpros_portignored (ROS1 compatibility stand-in)

Definition at line 139 of file client.py.

◆ myargv()

rosros.rospify.client.myargv (   argv = None)

Returns command-line arguments with remappings removed.

Parameters
argvarguments to use if not `sys.argv`
Returns
list of arguments with remappings removed

Definition at line 159 of file client.py.

◆ on_shutdown()

rosros.rospify.client.on_shutdown (   h)

Registers function to be called on shutdown, after node has been torn down.

Definition at line 170 of file client.py.

◆ search_param()

rosros.rospify.client.search_param (   param_name)

Search for a parameter on the node.

Parameters
param_nameparameter name
Returns
key of matching parameter or None if no matching parameter

Definition at line 180 of file client.py.

◆ set_param()

rosros.rospify.client.set_param (   param_name,
  param_value 
)

Set a parameter on the node.

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_nameparameter name
param_valueparameter value

Definition at line 205 of file client.py.

◆ spin()

rosros.rospify.client.spin ( )

Spins ROS2 node forever.

Definition at line 218 of file client.py.

◆ wait_for_message()

rosros.rospify.client.wait_for_message (   topic,
  topic_type,
  timeout = None 
)

Receive one message from topic.

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

Parameters
topicname of topic
topic_typetopic type class
timeouttimeout time in seconds or ROS Duration
Returns
ROS message
Exceptions
ROSExceptionif specified timeout is exceeded
ROSInterruptExceptionif shutdown interrupts wait

Definition at line 235 of file client.py.

Variable Documentation

◆ _ROSPY_LOG_LEVEL_TO_PY_LEVEL

rosros.rospify.client._ROSPY_LOG_LEVEL_TO_PY_LEVEL
protected

Map rospy log level constants to Python logging level constants.

Definition at line 40 of file client.py.

◆ DEBUG

int rosros.rospify.client.DEBUG = 1

Definition at line 29 of file client.py.

◆ ERROR

int rosros.rospify.client.ERROR = 8

Definition at line 32 of file client.py.

◆ FATAL

int rosros.rospify.client.FATAL = 16

Definition at line 33 of file client.py.

◆ get_param_cached

rosros.rospify.client.get_param_cached = get_param

Stand-in for `rospy.get_param_cached`.

Definition at line 96 of file client.py.

◆ INFO

int rosros.rospify.client.INFO = 2

Definition at line 30 of file client.py.

◆ WARN

int rosros.rospify.client.WARN = 4

Definition at line 31 of file client.py.