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

ROS system and node functionality. More...

Functions

 create_client (service, cls_or_typename, **qosargs)
 Returns a ROS service client instance, for invoking a service.
 
 create_publisher (topic, cls_or_typename, latch=False, queue_size=0, **qosargs)
 Returns a ROS publisher instance.
 
 create_rate (frequency)
 Returns a ROS rate instance, for sleeping at a fixed rate.
 
 create_service (service, cls_or_typename, callback, **qosargs)
 Returns a ROS service server instance, for providing a service.
 
 create_subscriber (topic, cls_or_typename, callback, callback_args=None, queue_size=0, raw=False, **qosargs)
 Returns a ROS subscriber instance.
 
 create_timer (period, callback, oneshot=False, immediate=False)
 Returns a ROS timer instance.
 
 delete_param (name)
 Deletes parameter from the node.
 
 destroy_entity (item)
 Closes the given publisher, subscriber, service client, or service server instance.
 
 get_logger ()
 Returns `logging.Logger` for logging to ROS log handler.
 
 get_namespace ()
 Returns ROS node namespace.
 
 get_node_name ()
 Returns ROS node full name with namespace.
 
 get_nodes ()
 Returns all ROS nodes, as `[node full name, ]`.
 
 get_param (name, default=None, autoset=True)
 Returns parameter value from the node.
 
 get_param_names ()
 Returns the names of all parameters on the node.
 
 get_params (nested=True)
 Returns the current ROS node parameters, by default as nested dictionary.
 
 get_ros_version ()
 Returns ROS version information, as {"major": "1" / "2", ?"minor": distro like "noetic"}.
 
 get_rostime ()
 Returns ROS time instance for current ROS clock time.
 
 get_services (node=None, namespace=None, include_types=True)
 Returns all available ROS services, as `[(service name, [type name, ]), ]`.
 
 get_topics ()
 Returns all available ROS topics, as `[(topic name, [type name, ]), ]`.
 
 has_param (name)
 Returns whether the parameter exists on the node.
 
 init_node (name, args=None, namespace=None, anonymous=False, log_level=None, enable_rosout=True, multithreaded=True, reentrant=False)
 Initializes ROS and creates ROS node.
 
 init_params (defaults=None, **defaultkws)
 Sets all parameters on node from defaults dictionary.
 
 ok ()
 Returns whether ROS has been initialized and is not shut down.
 
 on_shutdown (callback, *args, **kwargs)
 Registers function to be called on shutdown, after node has been torn down.
 
 register_init (node=None)
 Informs `rosros` of ROS having been initialized outside of `init_node()`.
 
 remap_name (name, namespace=None)
 Returns the absolute remapped topic/service name if mapping exists.
 
 resolve_name (name, namespace=None)
 Returns absolute remapped name, namespaced under current node if relative or private.
 
 set_param (name, value, descriptor=None)
 Sets a parameter on the node.
 
 shutdown (reason=None)
 Shuts down live ROS node, if any.
 
 sleep (duration)
 Sleeps for the specified duration in ROS time.
 
 spin ()
 Spins ROS node forever.
 
 spin_once (timeout=None)
 Waits until timeout in ROS1; executes one ROS operation or waits until timeout in ROS2.
 
 spin_until_future_complete (future, timeout=None)
 Spins ROS until future complete or timeout reached or ROS shut down.
 
 start_spin ()
 Sets ROS node spinning forever in a background thread.
 
 wait_for_publisher (topic, timeout=None, cls_or_typename=None)
 Blocks until topic has at least one publisher.
 
 wait_for_service (service, timeout=None, cls_or_typename=None)
 Blocks until service is available.
 
 wait_for_subscriber (topic, timeout=None, cls_or_typename=None)
 Blocks until topic has at least one subscriber.
 

Variables

 AnyMsg = ros.AnyMsg
 rospy.AnyMsg in ROS1, equivalent stand-in in ROS2
 
 Bag = ros.Bag
 rosbag.Bag in ROS1 (with some additional functionality), equivalent class in ROS2
 
 ros = ros1 or ros2
 
 ros1 = None
 

Detailed Description

ROS system and node functionality.

Function Documentation

◆ create_client()

rosros.core.create_client (   service,
  cls_or_typename,
**  qosargs 
)

Returns a ROS service client instance, for invoking a service.

Parameters
servicename of service to invoke
cls_or_typenameROS service class object like `std_srvs.srv.SetBool` or service type name like `"std_srvs/SetBool"
qosargsadditional key-value arguments for ROS2 `QoSProfile`, like `reliability` (ignored in ROS1)
Returns
`rospy.ServiceProxy` or `rclpy.client.Client`, either will have `call_async()` returning a future, either will support keyword arguments in calls and be callable itself

Definition at line 266 of file core.py.

◆ create_publisher()

rosros.core.create_publisher (   topic,
  cls_or_typename,
  latch = False,
  queue_size = 0,
**  qosargs 
)

Returns a ROS publisher instance.

Parameters
topicname of topic to open
cls_or_typenameROS message class object like `std_msgs.msg.Bool` or message type name like "std_msgs/Bool"
latchprovide last published message to new subscribers (sets `DurabilityPolicy.TRANSIENT_LOCAL` in ROS2)
queue_sizequeue size of outgoing messages (0 or None: infinite) (sets QoS `depth` in ROS2)
qosargsadditional key-value arguments for ROS2 `QoSProfile`, like `reliability` (uses only `depth` and `durability`=TRANSIENT_LOCAL in ROS1)
Returns
`rospy.Publisher` or `rclpy.publisher.Publisher`, either will support keyword arguments in `publish()` and have `get_num_connections()`

Definition at line 198 of file core.py.

◆ create_rate()

rosros.core.create_rate (   frequency)

Returns a ROS rate instance, for sleeping at a fixed rate.

Parameters
frequencyrate to sleep at, in Hz
Returns
`rospy.Rate` or `rclpy.rate.Rate`

Definition at line 288 of file core.py.

◆ create_service()

rosros.core.create_service (   service,
  cls_or_typename,
  callback,
**  qosargs 
)

Returns a ROS service server instance, for providing a service.

Parameters
servicename of service to provide
cls_or_typenameROS service class object like `std_srvs.srv.SetBool` or service type name like `"std_srvs/SetBool"
callbackcallback function, invoked with `(request, response)`, expected to return the populated response, or a list/tuple/dictionary for populating the response. If the function only takes one argument, it is invoked with `(request)`.
qosargsadditional key-value arguments for ROS2 `QoSProfile`, like `reliability` (ignored in ROS1)
Returns
`rospy.Service` or `rclpy.service.Service`

Definition at line 249 of file core.py.

◆ create_subscriber()

rosros.core.create_subscriber (   topic,
  cls_or_typename,
  callback,
  callback_args = None,
  queue_size = 0,
  raw = False,
**  qosargs 
)

Returns a ROS subscriber instance.

Parameters
topicname of topic to listen to
cls_or_typenameROS message class object like `std_msgs.msg.Bool` or message type name like "std_msgs/Bool"
callbackcallback function, invoked with received message, and with additional arguments if given
callback_argsadditional arguments to pass to the callback, if any, invoked as `callback(msg, callback_args)ยด
queue_sizequeue size of incoming messages (0 or None: infinite)
rawinvoke callback with serialized message bytes, make subscription with AnyMsg in ROS1
qosargsadditional key-value arguments for ROS2 `QoSProfile`, like `reliability` (uses only `depth` in ROS1). `__autodetect` will look up current publishers on the topic and create a compatible QoS.
Returns
`rospy.Subscriber` or `rclpy.subscription.Subscription`

Definition at line 225 of file core.py.

◆ create_timer()

rosros.core.create_timer (   period,
  callback,
  oneshot = False,
  immediate = False 
)

Returns a ROS timer instance.

Parameters
perioddesired period between callbacks, as seconds or ROS duration
callbackcallback function invoked on timer, with no arguments
oneshotwhether to fire only once
immediatewhether to fire once immediately instead of waiting one period
Returns
`rospy.Timer` or `rclpy.timer.Timer`

Definition at line 279 of file core.py.

◆ delete_param()

rosros.core.delete_param (   name)

Deletes parameter from the node.

Parameters
namefull name of the parameter in node namespace
Exceptions
KeyErrorif parameter not set

Definition at line 75 of file core.py.

◆ destroy_entity()

rosros.core.destroy_entity (   item)

Closes the given publisher, subscriber, service client, or service server instance.

Definition at line 292 of file core.py.

◆ get_logger()

rosros.core.get_logger ( )

Returns `logging.Logger` for logging to ROS log handler.

Logging methods on the logger (`debug()`, `info()`, etc) accept additional keyword arguments:

  • `__once__`: whether to log only once from call site
  • `__throttle__`: seconds to skip logging from call site for
  • `__throttle_identical__`: whether to skip logging identical consecutive texts from call site (given log message excluding formatting arguments). Combines with `__throttle__` to skip duplicates for a period.

Definition at line 307 of file core.py.

◆ get_namespace()

rosros.core.get_namespace ( )

Returns ROS node namespace.

Definition at line 316 of file core.py.

◆ get_node_name()

rosros.core.get_node_name ( )

Returns ROS node full name with namespace.

Definition at line 321 of file core.py.

◆ get_nodes()

rosros.core.get_nodes ( )

Returns all ROS nodes, as `[node full name, ]`.

Definition at line 326 of file core.py.

◆ get_param()

rosros.core.get_param (   name,
  default = None,
  autoset = True 
)

Returns parameter value from the node.

Parameters
defaultoptional default to return if parameter unknown
autosetset default value to node as parameter value if unknown
Returns
parameter value, or default if parameter was unknown
Exceptions
KeyErrorif parameter not set and default not given

Definition at line 110 of file core.py.

◆ get_param_names()

rosros.core.get_param_names ( )

Returns the names of all parameters on the node.

Definition at line 88 of file core.py.

◆ get_params()

rosros.core.get_params (   nested = True)

Returns the current ROS node parameters, by default as nested dictionary.

Parameters
nestedreturn a nested dictionary, like {"name": 1}}` vs {"my.name": 1}

Definition at line 98 of file core.py.

◆ get_ros_version()

rosros.core.get_ros_version ( )

Returns ROS version information, as {"major": "1" / "2", ?"minor": distro like "noetic"}.

Definition at line 331 of file core.py.

◆ get_rostime()

rosros.core.get_rostime ( )

Returns ROS time instance for current ROS clock time.

Definition at line 311 of file core.py.

◆ get_services()

rosros.core.get_services (   node = None,
  namespace = None,
  include_types = True 
)

Returns all available ROS services, as `[(service name, [type name, ]), ]`.

Parameters
nodefull name of the node to return services for, if any
namespacefull or partial namespace to scope services from
include_typesif false, type names will be returned as an empty list

Definition at line 350 of file core.py.

◆ get_topics()

rosros.core.get_topics ( )

Returns all available ROS topics, as `[(topic name, [type name, ]), ]`.

Definition at line 338 of file core.py.

◆ has_param()

rosros.core.has_param (   name)

Returns whether the parameter exists on the node.

Parameters
namefull name of the parameter in node namespace

Definition at line 84 of file core.py.

◆ init_node()

rosros.core.init_node (   name,
  args = None,
  namespace = None,
  anonymous = False,
  log_level = None,
  enable_rosout = True,
  multithreaded = True,
  reentrant = False 
)

Initializes ROS and creates ROS node.

Parameters
namenode name, without namespace
argslist of command-line arguments for the node
namespacenode namespace override
anonymouswhether to auto-generate a unique name for the node, using the given name as base
log_levellevel to set for ROS logging (name like "DEBUG" or one of `logging` constants like `logging.DEBUG`)
enable_rosout`False` to suppress auto-publication of rosout
multithreadedROS2 only, ignored in ROS1: use `MultiThreadedExecutor` instead of `SingleThreadedExecutor`
reentrantROS2 only, ignored in ROS1: use `ReentrantCallbackGroup` instead of `MutuallyExclusiveCallbackGroup`
Returns
`None` in ROS1, `rclpy.node.Node` in ROS2

Definition at line 48 of file core.py.

◆ init_params()

rosros.core.init_params (   defaults = None,
**  defaultkws 
)

Sets all parameters on node from defaults dictionary.

In ROS2, auto-declares unregistered parameters.

Parameters
defaultsnested dictionary with suitable keys and values for ROS (keys must be valid namespace names, list values must not contain nested values)
defaultkwsparameters as key=value
Returns
full nested parameters dictionary, combined from given defaults and externally set parameters on the node

Definition at line 66 of file core.py.

◆ ok()

rosros.core.ok ( )

Returns whether ROS has been initialized and is not shut down.

Definition at line 157 of file core.py.

◆ on_shutdown()

rosros.core.on_shutdown (   callback,
args,
**  kwargs 
)

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

Function is called with given arguments.

Note
function may not get called if process is killed.

Definition at line 169 of file core.py.

◆ register_init()

rosros.core.register_init (   node = None)

Informs `rosros` of ROS having been initialized outside of `init_node()`.

Parameters
nodemandatory `rclpy.node.Node` in ROS2

Definition at line 379 of file core.py.

◆ remap_name()

rosros.core.remap_name (   name,
  namespace = None 
)

Returns the absolute remapped topic/service name if mapping exists.

Parameters
namename to seek exact remapping for
namespacenamespace to resolve relative and private names to, by default current node namespace
Returns
remapped resolved name, or original if not mapped

Definition at line 361 of file core.py.

◆ resolve_name()

rosros.core.resolve_name (   name,
  namespace = None 
)

Returns absolute remapped name, namespaced under current node if relative or private.

Parameters
namespacenamespace to use if not current node full name

Definition at line 370 of file core.py.

◆ set_param()

rosros.core.set_param (   name,
  value,
  descriptor = None 
)

Sets a parameter on the node.

In ROS2, parameter will be auto-declared if unknown so far.

Parameters
namefull name of the parameter in node namespace
valueparameter value to set
descriptoroptional `rcl_interfaces.msg.ParameterDescriptor` in ROS2
Returns
the set value

Definition at line 123 of file core.py.

◆ shutdown()

rosros.core.shutdown (   reason = None)

Shuts down live ROS node, if any.

Parameters
reasonshutdown reason to log, if any

Definition at line 178 of file core.py.

◆ sleep()

rosros.core.sleep (   duration)

Sleeps for the specified duration in ROS time.

Raises error on ROS shutdown or ROS time jumping backwards

Parameters
durationtime to sleep, as seconds or ROS duration, <=0 returns immediately

Definition at line 390 of file core.py.

◆ spin()

rosros.core.spin ( )

Spins ROS node forever.

Definition at line 133 of file core.py.

◆ spin_once()

rosros.core.spin_once (   timeout = None)

Waits until timeout in ROS1; executes one ROS operation or waits until timeout in ROS2.

Parameters
timeouttime to wait at most, as seconds or ROS duration; None or <0 waits forever

Definition at line 143 of file core.py.

◆ spin_until_future_complete()

rosros.core.spin_until_future_complete (   future,
  timeout = None 
)

Spins ROS until future complete or timeout reached or ROS shut down.

Parameters
futureobject with `concurrent.futures.Future`-conforming interface to complete
timeouttime to wait, as seconds or ROS1 duration

Definition at line 153 of file core.py.

◆ start_spin()

rosros.core.start_spin ( )

Sets ROS node spinning forever in a background thread.

Definition at line 128 of file core.py.

◆ wait_for_publisher()

rosros.core.wait_for_publisher (   topic,
  timeout = None,
  cls_or_typename = None 
)

Blocks until topic has at least one publisher.

Parameters
topicname of topic to open
timeouttime to wait at most, as seconds or ROS duration; None or <0 waits forever
cls_or_typenamemessage type to expect if any, as ROS message class object like `std_msgs.msg.Bool` or message type name like "std_msgs/Bool"
Returns
whether a publisher is available

Definition at line 404 of file core.py.

◆ wait_for_service()

rosros.core.wait_for_service (   service,
  timeout = None,
  cls_or_typename = None 
)

Blocks until service is available.

Parameters
servicename of service
timeouttime to wait at most, as seconds or ROS duration; None or <0 waits forever
cls_or_typenameservice type to expect if any, as ROS service class object like `std_msgs.msg.Bool` or service type name like "std_srvs/SetBool"
Returns
whether the service is available

Definition at line 432 of file core.py.

◆ wait_for_subscriber()

rosros.core.wait_for_subscriber (   topic,
  timeout = None,
  cls_or_typename = None 
)

Blocks until topic has at least one subscriber.

Parameters
topicname of topic to open
timeouttime to wait at most, as seconds or ROS duration; None or <0 waits forever
cls_or_typenamemessage type to expect if any, as ROS message class object like `std_msgs.msg.Bool` or message type name like "std_msgs/Bool"
Returns
whether a subscriber is available

Definition at line 418 of file core.py.

Variable Documentation

◆ AnyMsg

rosros.core.AnyMsg = ros.AnyMsg

rospy.AnyMsg in ROS1, equivalent stand-in in ROS2

Definition at line 26 of file core.py.

◆ Bag

rosros.core.Bag = ros.Bag

rosbag.Bag in ROS1 (with some additional functionality), equivalent class in ROS2

Definition at line 29 of file core.py.

◆ ros

rosros.core.ros = ros1 or ros2

Definition at line 22 of file core.py.

◆ ros1

rosros.core.ros1 = None

Definition at line 17 of file core.py.