Utilities

rclpy.utilities.get_available_rmw_implementations() Set[str]

Return the set of all available RMW implementations as registered in the ament index.

The result can be overridden by setting an environment variable named RMW_IMPLEMENTATIONS. The variable can contain RMW implementation names separated by the platform specific path separator.

Raises:

RuntimeError – if the environment variable includes a missing RMW implementation.

rclpy.utilities.get_default_context(*, shutting_down=False) Context

Return the global default context singleton.

rclpy.utilities.get_rmw_implementation_identifier() str

Return the identifier of the current RMW implementation.

rclpy.utilities.ok(*, context: Context | None = None) bool

Return True if the given Context is initialized and not shut down.

Parameters:

context – a Context to check, else the global default context is used.

Returns:

True if the context is valid.

rclpy.utilities.remove_ros_args(args: Sequence[str] | None = None) List[str]

Return a list of only the non-ROS command line arguments.

Parameters:

args – A list of command line arguments to filter from. If None then sys.argv is used instead.

Returns:

A list of all command line arguments that are not used by ROS.

rclpy.utilities.shutdown(*, context=None) None

Shutdown the given Context.

Parameters:

context – a Context to check, else the global default context is used.

rclpy.utilities.timeout_sec_to_nsec(timeout_sec: float | None) int

Convert timeout in seconds to rcl compatible timeout in nanoseconds.

Python tends to use floating point numbers in seconds for timeouts. This utility converts a python-style timeout to an integer in nanoseconds that can be used by rcl_wait.

Parameters:

timeout_sec – Seconds to wait. Block forever if None or negative. Don’t wait if < 1ns

Returns:

rcl_wait compatible timeout in nanoseconds

rclpy.utilities.try_shutdown(*, context=None) None

Shutdown the given Context if not already shutdown.

Parameters:

context – a Context to check, else the global default context is used.