rosros 0.2.5
Simple unified interface to ROS1 / ROS2 Python API
|
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() | |
ROS1 core interface.
rosros.ros1.canonical | ( | typename | ) |
rosros.ros1.create_client | ( | service, | |
cls_or_typename | |||
) |
Returns a ROS1 service client instance, for invoking a service.
service | name of service to invoke |
cls_or_typename | ROS1 service class object like `std_srvs.srv.SetBool` or service type name like `"std_srvs/SetBool" |
rosros.ros1.create_publisher | ( | topic, | |
cls_or_typename, | |||
latch = False , |
|||
queue_size = 0 |
|||
) |
Returns a ROS1 publisher instance.
topic | name of topic to open |
cls_or_typename | ROS1 message class object like `std_msgs.msg.Bool` or message type name like "std_msgs/Bool" |
latch | provide last published message to new subscribers |
queue_size | queue size of outgoing messages (0 or None: infinite) |
rosros.ros1.create_rate | ( | frequency | ) |
rosros.ros1.create_service | ( | service, | |
cls_or_typename, | |||
callback | |||
) |
Returns a ROS1 service server instance, for providing a service.
service | name of service to provide |
cls_or_typename | ROS1 service class object like `std_srvs.srv.SetBool` or service type name like `"std_srvs/SetBool" |
callback | callback function, invoked with (req, resp) or (req) |
rosros.ros1.create_subscriber | ( | topic, | |
cls_or_typename, | |||
callback, | |||
callback_args = None , |
|||
queue_size = 0 , |
|||
raw = False |
|||
) |
Returns a ROS1 subscriber instance.
topic | name of topic to listen to |
cls_or_typename | ROS1 message class object like `std_msgs.msg.Bool` or message type name like "std_msgs/Bool" |
callback | callback function, invoked with received message, and with additional arguments if given |
callback_args | additional arguments to pass to the callback, if any, invoked as `callback(msg, callback_args)ยด |
raw | make subscription with AnyMsg, invoke callback with serialized message bytes |
queue_size | queue size of incoming messages (0 or None: infinite) |
rosros.ros1.create_timer | ( | period, | |
callback, | |||
oneshot = False , |
|||
immediate = False |
|||
) |
Returns a ROS1 timer instance.
period | desired period between callbacks, as seconds or ROS1 duration |
callback | callback function invoked on timer, with no arguments |
oneshot | whether to fire only once |
immediate | whether to fire once immediately instead of waiting one period |
rosros.ros1.delete_param | ( | name | ) |
rosros.ros1.deserialize_message | ( | raw, | |
cls_or_typename | |||
) |
rosros.ros1.destroy_entity | ( | item | ) |
rosros.ros1.format_param_name | ( | name | ) |
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:
rosros.ros1.get_message_class | ( | msg_or_type | ) |
Returns ROS1 message / service class object.
msg_or_type | full 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` |
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.
msg_or_type | canonical 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` |
full | include definitions of nested types, separated by "\n---\nMSG: pkg/Type\n" (ignored for service request/response types) |
rosros.ros1.get_message_fields | ( | val | ) |
rosros.ros1.get_message_header | ( | val | ) |
rosros.ros1.get_message_type | ( | msg_or_cls | ) |
Returns ROS1 message / service canonical type name, like "std_msgs/Header".
Returns "*" for `AnyMsg`.
msg_or_cls | class instance like `std_msgs.msg.Bool()`, or class object like `std_msgs.msg.Bool` |
rosros.ros1.get_message_type_hash | ( | msg_or_type | ) |
rosros.ros1.get_message_value | ( | msg, | |
name, | |||
default = ... |
|||
) |
rosros.ros1.get_node_name | ( | ) |
rosros.ros1.get_nodes | ( | ) |
rosros.ros1.get_param | ( | name, | |
default = None , |
|||
autoset = True |
|||
) |
Returns parameter value from current ROS1 node.
name | full name of the parameter in node namespace |
default | optional default to return if parameter unknown |
autoset | set default value to node parameter if unknown |
KeyError | if parameter not set and default not given |
rosros.ros1.get_param_names | ( | ) |
rosros.ros1.get_params | ( | nested = True | ) |
rosros.ros1.get_rostime | ( | ) |
rosros.ros1.get_service_definition | ( | srv_or_type | ) |
Returns ROS1 service type definition text.
srv_or_type | canonical 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` |
rosros.ros1.get_service_request_class | ( | srv_or_type | ) |
Returns ROS1 service request class object.
srv_or_type | canonical 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` |
rosros.ros1.get_service_response_class | ( | srv_or_type | ) |
Returns ROS1 service response class object.
srv_or_type | canonical 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` |
rosros.ros1.get_services | ( | node = None , |
|
namespace = None , |
|||
include_types = True |
|||
) |
Returns all available ROS1 services, as `[(service name, [type name, ]), ]`.
node | full name of the node to return services for, if any |
namespace | full or partial namespace to scope services from |
include_types | if false, type names will be returned as an empty list |
rosros.ros1.get_topics | ( | ) |
rosros.ros1.has_param | ( | name | ) |
rosros.ros1.init_node | ( | name, | |
args = None , |
|||
namespace = None , |
|||
anonymous = False , |
|||
log_level = None , |
|||
enable_rosout = True |
|||
) |
Initializes rospy and creates ROS1 node.
name | node name, without namespace |
args | list of command-line arguments for the node |
namespace | node namespace override |
anonymous | whether to auto-generate a unique name for the node, using the given name as base |
log_level | level 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 |
rosros.ros1.init_params | ( | defaults = None , |
|
** | defaultkws | ||
) |
Declares all parameters on node from defaults dictionary.
defaults | nested dictionary with suitable keys and values for ROS (keys must be valid namespace names, list values must not contain nested values) |
defaultkws | parameters as key=value |
rosros.ros1.is_ros_message | ( | val | ) |
Returns whether value is a ROS1 message or service request/response class or instance.
val | like `std_msgs.msg.Bool()` or `std_srvs.srv.SetBoolRequest` |
rosros.ros1.is_ros_service | ( | val | ) |
rosros.ros1.is_ros_time | ( | val | ) |
rosros.ros1.make_duration | ( | secs = 0 , |
|
nsecs = 0 |
|||
) |
rosros.ros1.make_time | ( | secs = 0 , |
|
nsecs = 0 |
|||
) |
rosros.ros1.ok | ( | ) |
rosros.ros1.on_shutdown | ( | callback, | |
* | args, | ||
** | kwargs | ||
) |
rosros.ros1.register_init | ( | ) |
rosros.ros1.remap_name | ( | name, | |
namespace = None |
|||
) |
Returns the absolute remapped topic/service name if mapping exists.
name | name to seek exact remapping for |
namespace | namespace to resolve relative and private names to, by default current node namespace |
rosros.ros1.resolve_name | ( | name, | |
namespace = None |
|||
) |
rosros.ros1.scalar | ( | typename | ) |
rosros.ros1.serialize_message | ( | msg | ) |
rosros.ros1.set_param | ( | name, | |
value | |||
) |
rosros.ros1.shutdown | ( | reason = None | ) |
rosros.ros1.sleep | ( | duration | ) |
rosros.ros1.spin_once | ( | timeout = None | ) |
rosros.ros1.spin_until_future_complete | ( | future, | |
timeout = None |
|||
) |
rosros.ros1.start_spin | ( | ) |
rosros.ros1.to_duration | ( | val | ) |
rosros.ros1.to_nsec | ( | val | ) |
rosros.ros1.to_sec | ( | val | ) |
rosros.ros1.to_sec_nsec | ( | val | ) |
rosros.ros1.to_time | ( | val | ) |
rosros.ros1.wait_for_publisher | ( | topic, | |
timeout = None , |
|||
cls_or_typename = None |
|||
) |
Blocks until topic has at least one publisher.
topic | name of topic to open |
timeout | time to wait at most, as seconds or ROS duration; None or <0 waits forever |
cls_or_typename | message type to expect if any, as ROS message class object like `std_msgs.msg.Bool` or message type name like "std_msgs/Bool" |
rosros.ros1.wait_for_service | ( | service, | |
timeout = None , |
|||
cls_or_typename = None |
|||
) |
Blocks until service is available.
service | name of service |
timeout | time to wait at most, as seconds or ROS duration; None or <0 waits forever |
cls_or_typename | service type to expect if any, as ROS service class object like `std_msgs.msg.Bool` or service type name like "std_srvs/SetBool" |
rosros.ros1.wait_for_subscriber | ( | topic, | |
timeout = None , |
|||
cls_or_typename = None |
|||
) |
Blocks until topic has at least one subscriber.
topic | name of topic to open |
timeout | time to wait at most, as seconds or ROS duration; None or <0 waits forever |
cls_or_typename | message type to expect if any, as ROS message class object like `std_msgs.msg.Bool` or message type name like "std_msgs/Bool" |
str rosros.ros1.FAMILY = "rospy" |
str rosros.ros1.PARAM_SEPARATOR = "/" |
str rosros.ros1.PRIVATE_PREFIX = "~" |
dict rosros.ros1.PY_LOG_LEVEL_TO_ROSPY_LEVEL |
dict rosros.ros1.ROS_ALIAS_TYPES = {"byte": "int8", "char": "uint8"} |
dict rosros.ros1.ROS_TIME_CLASSES = {rospy.Time: "time", rospy.Duration: "duration"} |
list rosros.ros1.ROS_TIME_TYPES = ["time", "duration"] |