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

ROS1 core interface. More...

Classes

class  Bag
 ROS1 bag reader and writer. More...
 
class  Mutex
 Container for local mutexes. More...
 
class  ROSLogHandler
 Logging handler that forwards logging messages to ROS1 logger. More...
 

Functions

 canonical (typename)
 Returns "pkg/Type" for "pkg/subdir/Type".
 
 create_client (service, cls_or_typename)
 Returns a ROS1 service client instance, for invoking a service.
 
 create_publisher (topic, cls_or_typename, latch=False, queue_size=0)
 Returns a ROS1 publisher instance.
 
 create_rate (frequency)
 Returns a ROS1 rate instance, for sleeping at a fixed rate.
 
 create_service (service, cls_or_typename, callback)
 Returns a ROS1 service server instance, for providing a service.
 
 create_subscriber (topic, cls_or_typename, callback, callback_args=None, queue_size=0, raw=False)
 Returns a ROS1 subscriber instance.
 
 create_timer (period, callback, oneshot=False, immediate=False)
 Returns a ROS1 timer instance.
 
 delete_param (name)
 Deletes parameter from the node.
 
 deserialize_message (raw, cls_or_typename)
 Returns ROS1 message or service request/response instantiated from serialized binary.
 
 destroy_entity (item)
 Closes the given publisher, subscriber, service client, or service server instance.
 
 format_param_name (name)
 Returns parameter name using "/" separator, and leading root or private sigils stripped.
 
 get_logger ()
 Returns `logging.Logger` for logging to ROS1 log handler.
 
 get_message_class (msg_or_type)
 Returns ROS1 message / service class object.
 
 get_message_definition (msg_or_type, full=True)
 Returns ROS1 message or service request/response type definition text.
 
 get_message_fields (val)
 Returns {field name: field type name} if ROS1 message or service request/response, else {}.
 
 get_message_header (val)
 Returns message `std_msgs/Header`-attribute if any, else `None`.
 
 get_message_type (msg_or_cls)
 Returns ROS1 message / service canonical type name, like "std_msgs/Header".
 
 get_message_type_hash (msg_or_type)
 Returns ROS1 message / service type MD5 hash.
 
 get_message_value (msg, name, default=...)
 Returns object attribute value, with numeric arrays converted to lists.
 
 get_namespace ()
 Returns ROS1 node namespace.
 
 get_node_name ()
 Returns ROS1 node full name with namespace.
 
 get_nodes ()
 Returns all ROS1 nodes, as `[node full name, ]`.
 
 get_param (name, default=None, autoset=True)
 Returns parameter value from current ROS1 node.
 
 get_param_names ()
 Returns the names of all current ROS1 node parameters.
 
 get_params (nested=True)
 Returns the current ROS1 node parameters, by default as nested dictionary.
 
 get_rostime ()
 Returns current ROS1 time, as `rospy.Time`.
 
 get_service_definition (srv_or_type)
 Returns ROS1 service type definition text.
 
 get_service_request_class (srv_or_type)
 Returns ROS1 service request class object.
 
 get_service_response_class (srv_or_type)
 Returns ROS1 service response class object.
 
 get_services (node=None, namespace=None, include_types=True)
 Returns all available ROS1 services, as `[(service name, [type name, ]), ]`.
 
 get_topics ()
 Returns all available ROS1 topics, as `[(topic name, [type name, ]), ]`.
 
 has_param (name)
 Returns whether the parameter exists.
 
 init_node (name, args=None, namespace=None, anonymous=False, log_level=None, enable_rosout=True)
 Initializes rospy and creates ROS1 node.
 
 init_params (defaults=None, **defaultkws)
 Declares all parameters on node from defaults dictionary.
 
 is_ros_message (val)
 Returns whether value is a ROS1 message or service request/response class or instance.
 
 is_ros_service (val)
 Returns whether value is a ROS1 service class object or instance.
 
 is_ros_time (val)
 Returns whether value is a ROS1 time/duration class or instance.
 
 make_duration (secs=0, nsecs=0)
 Returns a ROS1 duration, as rospy.Duration.
 
 make_time (secs=0, nsecs=0)
 Returns a ROS1 time, as rospy.Time.
 
 ok ()
 Returns whether ROS1 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 ()
 Informs `rosros` of ROS1 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.
 
 scalar (typename)
 Returns scalar type from ROS message data type, like "uint8" from "uint8[100]".
 
 serialize_message (msg)
 Returns ROS1 message or service request/response as a serialized binary of `bytes()`.
 
 set_param (name, value)
 Sets a parameter on the node.
 
 shutdown (reason=None)
 Sends the shutdown signal to rospy.
 
 sleep (duration)
 Sleeps for the specified duration in ROS time.
 
 spin ()
 Spins ROS1 forever.
 
 spin_once (timeout=None)
 Waits until timeout, or forever if timeout None or negative.
 
 spin_until_future_complete (future, timeout=None)
 Spins ROS1 until future complete or timeout reached or ROS shut down.
 
 start_spin ()
 Sets ROS1 spinning forever in a background thread.
 
 to_duration (val)
 Returns value as ROS1 duration if convertible (int/float/time/datetime/decimal), else value.
 
 to_nsec (val)
 Returns value in nanoseconds if value is ROS1 time/duration, else value.
 
 to_sec (val)
 Returns value in seconds if value is ROS1 time/duration, else value.
 
 to_sec_nsec (val)
 Returns value as (seconds, nanoseconds) if value is ROS1 time/duration, else value.
 
 to_time (val)
 Returns value as ROS1 time if convertible (int/float/duration/datetime/decimal), else value.
 
 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 = rospy.AnyMsg
 `rospy.AnyMsg`
 
str FAMILY = "rospy"
 ROS Python module family, "rospy".
 
 MASTER = None
 rospy.MasterProxy instance
 
str PARAM_SEPARATOR = "/"
 Separator char between ROS1 parameter namespace parts.
 
str PRIVATE_PREFIX = "~"
 Prefix for "private" names, auto-namespaced under current namespace.
 
dict PY_LOG_LEVEL_TO_ROSPY_LEVEL
 Map rospy log level constants to Python logging level constants.
 
dict ROS_ALIAS_TYPES = {"byte": "int8", "char": "uint8"}
 Mapping between ROS type aliases and real types, like {"byte": "int8"}.
 
dict ROS_TIME_CLASSES = {rospy.Time: "time", rospy.Duration: "duration"}
 ROS1 time/duration types mapped to type names.
 
list ROS_TIME_TYPES = ["time", "duration"]
 ROS1 time/duration types.
 
 SPINNER = None
 `threading.Thread` for start_spin()
 

Detailed Description

ROS1 core interface.

Function Documentation

◆ canonical()

rosros.ros1.canonical (   typename)

Returns "pkg/Type" for "pkg/subdir/Type".

Definition at line 916 of file ros1.py.

◆ create_client()

rosros.ros1.create_client (   service,
  cls_or_typename 
)

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

Parameters
servicename of service to invoke
cls_or_typenameROS1 service class object like `std_srvs.srv.SetBool` or service type name like `"std_srvs/SetBool"
Returns
`rospy.ServiceProxy`, will have `call_async()` returning a future

Definition at line 630 of file ros1.py.

◆ create_publisher()

rosros.ros1.create_publisher (   topic,
  cls_or_typename,
  latch = False,
  queue_size = 0 
)

Returns a ROS1 publisher instance.

Parameters
topicname of topic to open
cls_or_typenameROS1 message class object like `std_msgs.msg.Bool` or message type name like "std_msgs/Bool"
latchprovide last published message to new subscribers
queue_sizequeue size of outgoing messages (0 or None: infinite)
Returns
`rospy.Publisher`

Definition at line 661 of file ros1.py.

◆ create_rate()

rosros.ros1.create_rate (   frequency)

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

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

Definition at line 712 of file ros1.py.

◆ create_service()

rosros.ros1.create_service (   service,
  cls_or_typename,
  callback 
)

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

Parameters
servicename of service to provide
cls_or_typenameROS1 service class object like `std_srvs.srv.SetBool` or service type name like `"std_srvs/SetBool"
callbackcallback function, invoked with (req, resp) or (req)
Returns
`rospy.Service`

Definition at line 642 of file ros1.py.

◆ create_subscriber()

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

Returns a ROS1 subscriber instance.

Parameters
topicname of topic to listen to
cls_or_typenameROS1 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)ยด
rawmake subscription with AnyMsg, invoke callback with serialized message bytes
queue_sizequeue size of incoming messages (0 or None: infinite)
Returns
`rospy.Subscriber`

Definition at line 680 of file ros1.py.

◆ create_timer()

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

Returns a ROS1 timer instance.

Parameters
perioddesired period between callbacks, as seconds or ROS1 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`

Definition at line 698 of file ros1.py.

◆ delete_param()

rosros.ros1.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 526 of file ros1.py.

◆ deserialize_message()

rosros.ros1.deserialize_message (   raw,
  cls_or_typename 
)

Returns ROS1 message or service request/response instantiated from serialized binary.

Definition at line 1123 of file ros1.py.

◆ destroy_entity()

rosros.ros1.destroy_entity (   item)

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

Definition at line 716 of file ros1.py.

◆ format_param_name()

rosros.ros1.format_param_name (   name)

Returns parameter name using "/" separator, and leading root or private sigils stripped.

Definition at line 924 of file ros1.py.

◆ get_logger()

rosros.ros1.get_logger ( )

Returns `logging.Logger` for logging to ROS1 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 781 of file ros1.py.

◆ get_message_class()

rosros.ros1.get_message_class (   msg_or_type)

Returns ROS1 message / service class object.

Parameters
msg_or_typefull or canonical class name like "std_msgs/Bool" or "std_srvs/SetBool" or "std_srvs/SetBoolRequest", or class instance like `std_msgs.msg.Bool()`, or class object like `std_msgs.msg.Bool`
Returns
ROS1 message / service class object, like `std_msgs.msg.Bool` or `std_srvs.srv.SetBool` or `std_srvs.srv.SetBoolRequest`, or None if not found

Definition at line 939 of file ros1.py.

◆ get_message_definition()

rosros.ros1.get_message_definition (   msg_or_type,
  full = True 
)

Returns ROS1 message or service request/response type definition text.

Text will include subtype definitions by default.

Parameters
msg_or_typecanonical or full class name like "std_msgs/Bool" or "std_msgs/msg/Bool", or class instance like `std_msgs.msg.Bool()`, or class object like `std_msgs.msg.Bool`
fullinclude definitions of nested types, separated by "\n---\nMSG: pkg/Type\n" (ignored for service request/response types)
Returns
message type definition text

Definition at line 970 of file ros1.py.

◆ get_message_fields()

rosros.ros1.get_message_fields (   val)

Returns {field name: field type name} if ROS1 message or service request/response, else {}.

Parameters
valROS1 message or service request/response instance, or class object

Definition at line 982 of file ros1.py.

◆ get_message_header()

rosros.ros1.get_message_header (   val)

Returns message `std_msgs/Header`-attribute if any, else `None`.

Parameters
valROS message or service request/response instance

Definition at line 994 of file ros1.py.

◆ get_message_type()

rosros.ros1.get_message_type (   msg_or_cls)

Returns ROS1 message / service canonical type name, like "std_msgs/Header".

Returns "*" for `AnyMsg`.

Parameters
msg_or_clsclass instance like `std_msgs.msg.Bool()`, or class object like `std_msgs.msg.Bool`
Returns
canonical name, or `None` if not ROS message / service

Definition at line 1010 of file ros1.py.

◆ get_message_type_hash()

rosros.ros1.get_message_type_hash (   msg_or_type)

Returns ROS1 message / service type MD5 hash.

Parameters
msg_or_typefull or canonical class name like "std_msgs/Bool" or "std_srvs/SetBool" or "std_srvs/SetBoolRequest", or class instance like `std_msgs.msg.Bool()`, or class object like `std_msgs.msg.Bool`

Definition at line 1024 of file ros1.py.

◆ get_message_value()

rosros.ros1.get_message_value (   msg,
  name,
  default = ... 
)

Returns object attribute value, with numeric arrays converted to lists.

Parameters
namemessage attribute name; may also be (nested, path) or "nested.path"
defaultvalue to return if attribute does not exist; raises exception otherwise

Definition at line 1034 of file ros1.py.

◆ get_namespace()

rosros.ros1.get_namespace ( )

Returns ROS1 node namespace.

Definition at line 726 of file ros1.py.

◆ get_node_name()

rosros.ros1.get_node_name ( )

Returns ROS1 node full name with namespace.

Definition at line 731 of file ros1.py.

◆ get_nodes()

rosros.ros1.get_nodes ( )

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

Definition at line 736 of file ros1.py.

◆ get_param()

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

Returns parameter value from current ROS1 node.

Parameters
namefull name of the parameter in node namespace
defaultoptional default to return if parameter unknown
autosetset default value to node parameter if unknown
Returns
parameter value, or default if parameter was unknown
Exceptions
KeyErrorif parameter not set and default not given

Definition at line 478 of file ros1.py.

◆ get_param_names()

rosros.ros1.get_param_names ( )

Returns the names of all current ROS1 node parameters.

Definition at line 485 of file ros1.py.

◆ get_params()

rosros.ros1.get_params (   nested = True)

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

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

Definition at line 499 of file ros1.py.

◆ get_rostime()

rosros.ros1.get_rostime ( )

Returns current ROS1 time, as `rospy.Time`.

Definition at line 785 of file ros1.py.

◆ get_service_definition()

rosros.ros1.get_service_definition (   srv_or_type)

Returns ROS1 service type definition text.

Parameters
srv_or_typecanonical or full class name like "std_srvs/SetBool" or "std_srvs/srv/SetBool", or class instance like `std_srvs.srv.SetBool()`, or class object like `std_srvs.srv.SetBool`
Returns
ROS service type definition text

Definition at line 1053 of file ros1.py.

◆ get_service_request_class()

rosros.ros1.get_service_request_class (   srv_or_type)

Returns ROS1 service request class object.

Parameters
srv_or_typecanonical or full class name like "std_srvs/SetBool" or "std_srvs/srv/SetBool", or class instance like `std_srvs.srv.SetBool()`, or class object like `std_srvs.srv.SetBool`
Returns
ROS1 service request class object, like `std_srvs.srv.SetBoolRequest`

Definition at line 1068 of file ros1.py.

◆ get_service_response_class()

rosros.ros1.get_service_response_class (   srv_or_type)

Returns ROS1 service response class object.

Parameters
srv_or_typecanonical or full class name like "std_srvs/SetBool" or "std_srvs/srv/SetBool", or class instance like `std_srvs.srv.SetBool()`, or class object like `std_srvs.srv.SetBool`
Returns
ROS1 service response class object, like `std_srvs.srv.SetBoolResponse`

Definition at line 1080 of file ros1.py.

◆ get_services()

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

Returns all available ROS1 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 757 of file ros1.py.

◆ get_topics()

rosros.ros1.get_topics ( )

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

Definition at line 742 of file ros1.py.

◆ has_param()

rosros.ros1.has_param (   name)

Returns whether the parameter exists.

Parameters
namefull name of the parameter in node namespace

Definition at line 465 of file ros1.py.

◆ init_node()

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

Initializes rospy and creates ROS1 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

Definition at line 391 of file ros1.py.

◆ init_params()

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

Declares all parameters on node from defaults dictionary.

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 436 of file ros1.py.

◆ is_ros_message()

rosros.ros1.is_ros_message (   val)

Returns whether value is a ROS1 message or service request/response class or instance.

Parameters
vallike `std_msgs.msg.Bool()` or `std_srvs.srv.SetBoolRequest`
Returns
True if value is a ROS1 message or service request/response class or instance, False otherwise

Definition at line 1090 of file ros1.py.

◆ is_ros_service()

rosros.ros1.is_ros_service (   val)

Returns whether value is a ROS1 service class object or instance.

Definition at line 1094 of file ros1.py.

◆ is_ros_time()

rosros.ros1.is_ros_time (   val)

Returns whether value is a ROS1 time/duration class or instance.

Definition at line 1101 of file ros1.py.

◆ make_duration()

rosros.ros1.make_duration (   secs = 0,
  nsecs = 0 
)

Returns a ROS1 duration, as rospy.Duration.

Definition at line 1106 of file ros1.py.

◆ make_time()

rosros.ros1.make_time (   secs = 0,
  nsecs = 0 
)

Returns a ROS1 time, as rospy.Time.

Definition at line 1111 of file ros1.py.

◆ ok()

rosros.ros1.ok ( )

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

Definition at line 530 of file ros1.py.

◆ on_shutdown()

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

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

Function is called with given arguments.

Definition at line 541 of file ros1.py.

◆ register_init()

rosros.ros1.register_init ( )

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

Definition at line 416 of file ros1.py.

◆ remap_name()

rosros.ros1.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 801 of file ros1.py.

◆ resolve_name()

rosros.ros1.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 810 of file ros1.py.

◆ scalar()

rosros.ros1.scalar (   typename)

Returns scalar type from ROS message data type, like "uint8" from "uint8[100]".

Returns type unchanged if already a scalar.

Definition at line 1134 of file ros1.py.

◆ serialize_message()

rosros.ros1.serialize_message (   msg)

Returns ROS1 message or service request/response as a serialized binary of `bytes()`.

Definition at line 1116 of file ros1.py.

◆ set_param()

rosros.ros1.set_param (   name,
  value 
)

Sets a parameter on the node.

Parameters
namefull name of the parameter in node namespace
valueparameter value to set
Returns
the set value

Definition at line 516 of file ros1.py.

◆ shutdown()

rosros.ros1.shutdown (   reason = None)

Sends the shutdown signal to rospy.

Parameters
reasonshutdown reason to log, if any

Definition at line 618 of file ros1.py.

◆ sleep()

rosros.ros1.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 832 of file ros1.py.

◆ spin()

rosros.ros1.spin ( )

Spins ROS1 forever.

Definition at line 565 of file ros1.py.

◆ spin_once()

rosros.ros1.spin_once (   timeout = None)

Waits until timeout, or forever if timeout None or negative.

Parameters
timeouttime to sleep, as seconds or ROS duration; None or <0 waits forever

Definition at line 585 of file ros1.py.

◆ spin_until_future_complete()

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

Spins ROS1 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 595 of file ros1.py.

◆ start_spin()

rosros.ros1.start_spin ( )

Sets ROS1 spinning forever in a background thread.

Does nothing if spinning has already been started.

Definition at line 551 of file ros1.py.

◆ to_duration()

rosros.ros1.to_duration (   val)

Returns value as ROS1 duration if convertible (int/float/time/datetime/decimal), else value.

Definition at line 1138 of file ros1.py.

◆ to_nsec()

rosros.ros1.to_nsec (   val)

Returns value in nanoseconds if value is ROS1 time/duration, else value.

Definition at line 1152 of file ros1.py.

◆ to_sec()

rosros.ros1.to_sec (   val)

Returns value in seconds if value is ROS1 time/duration, else value.

Definition at line 1157 of file ros1.py.

◆ to_sec_nsec()

rosros.ros1.to_sec_nsec (   val)

Returns value as (seconds, nanoseconds) if value is ROS1 time/duration, else value.

Definition at line 1162 of file ros1.py.

◆ to_time()

rosros.ros1.to_time (   val)

Returns value as ROS1 time if convertible (int/float/duration/datetime/decimal), else value.

Definition at line 1167 of file ros1.py.

◆ wait_for_publisher()

rosros.ros1.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 846 of file ros1.py.

◆ wait_for_service()

rosros.ros1.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 894 of file ros1.py.

◆ wait_for_subscriber()

rosros.ros1.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 870 of file ros1.py.

Variable Documentation

◆ AnyMsg

rosros.ros1.AnyMsg = rospy.AnyMsg

`rospy.AnyMsg`

Definition at line 45 of file ros1.py.

◆ FAMILY

str rosros.ros1.FAMILY = "rospy"

ROS Python module family, "rospy".

Definition at line 63 of file ros1.py.

◆ MASTER

rosros.ros1.MASTER = None

rospy.MasterProxy instance

Definition at line 75 of file ros1.py.

◆ PARAM_SEPARATOR

str rosros.ros1.PARAM_SEPARATOR = "/"

Separator char between ROS1 parameter namespace parts.

Definition at line 57 of file ros1.py.

◆ PRIVATE_PREFIX

str rosros.ros1.PRIVATE_PREFIX = "~"

Prefix for "private" names, auto-namespaced under current namespace.

Definition at line 60 of file ros1.py.

◆ PY_LOG_LEVEL_TO_ROSPY_LEVEL

dict rosros.ros1.PY_LOG_LEVEL_TO_ROSPY_LEVEL
Initial value:
1= {
2 logging.DEBUG: 1,
3 logging.INFO: 2,
4 logging.WARN: 4,
5 logging.ERROR: 8,
6 logging.FATAL: 16,
7}

Map rospy log level constants to Python logging level constants.

Definition at line 66 of file ros1.py.

◆ ROS_ALIAS_TYPES

dict rosros.ros1.ROS_ALIAS_TYPES = {"byte": "int8", "char": "uint8"}

Mapping between ROS type aliases and real types, like {"byte": "int8"}.

Definition at line 54 of file ros1.py.

◆ ROS_TIME_CLASSES

dict rosros.ros1.ROS_TIME_CLASSES = {rospy.Time: "time", rospy.Duration: "duration"}

ROS1 time/duration types mapped to type names.

Definition at line 51 of file ros1.py.

◆ ROS_TIME_TYPES

list rosros.ros1.ROS_TIME_TYPES = ["time", "duration"]

ROS1 time/duration types.

Definition at line 48 of file ros1.py.

◆ SPINNER

rosros.ros1.SPINNER = None

`threading.Thread` for start_spin()

Definition at line 78 of file ros1.py.