rclpy.node module

class rclpy.node.Node(node_name: str, *, context: Context | None = None, cli_args: List[str] | None = None, namespace: str | None = None, use_global_arguments: bool = True, enable_rosout: bool = True, rosout_qos_profile: rclpy.qos.QoSProfile | int | None = rclpy.qos.qos_profile_rosout_default, start_parameter_services: bool = True, parameter_overrides: List[Parameter[Any]] | None = None, allow_undeclared_parameters: bool = False, automatically_declare_parameters_from_overrides: bool = False, enable_logger_service: bool = False)

Bases: object

A Node in the ROS graph.

A Node is the primary entrypoint in a ROS system for communication. It can be used to create ROS entities such as publishers, subscribers, services, etc.

Create a Node.

Parameters:
  • node_name – A name to give to this node. Validated by validate_node_name().

  • context – The context to be associated with, or None for the default global context.

  • cli_args – A list of strings of command line args to be used only by this node. These arguments are used to extract remappings used by the node and other ROS specific settings, as well as user defined non-ROS arguments.

  • namespace – The namespace to which relative topic and service names will be prefixed. Validated by validate_namespace().

  • use_global_argumentsFalse if the node should ignore process-wide command line args.

  • enable_rosoutFalse if the node should ignore rosout logging.

  • rosout_qos_profile – A QoSProfile or a history depth to apply to rosout publisher. In the case that a history depth is provided, the QoS history is set to KEEP_LAST the QoS history depth is set to the value of the parameter, and all other QoS settings are set to their default value.

  • start_parameter_servicesFalse if the node should not create parameter services.

  • parameter_overrides – A list of overrides for initial values for parameters declared on the node.

  • allow_undeclared_parameters – True if undeclared parameters are allowed. This flag affects the behavior of parameter-related operations.

  • automatically_declare_parameters_from_overrides – If True, the “parameter overrides” will be used to implicitly declare parameters on the node during creation.

  • enable_logger_serviceTrue if ROS2 services are created to allow external nodes to get and set logger levels of this node. Otherwise, logger levels are only managed locally. That is, logger levels cannot be changed remotely.

PARAM_REL_TOL = 1e-06

Relative tolerance for floating point parameter values’ comparison. See math.isclose documentation.

add_on_set_parameters_callback(callback: Callable[[List[Parameter[Any]]], rcl_interfaces.msg.SetParametersResult]) None

Add a callback in front to the list of callbacks.

Calling this function will add a callback in self._on_set_parameter_callbacks list.

It is considered bad practice to reject changes for “unknown” parameters as this prevents other parts of the node (that may be aware of these parameters) from handling them.

Parameters:

callback – The function that is called whenever parameters are being validated for the node.

add_post_set_parameters_callback(callback: Callable[[List[Parameter[Any]]], None]) None

Add a callback gets triggered after parameters are set successfully.

Calling this function will add a callback in self._post_set_parameter_callbacks list.

The callback signature is designed to allow handling of the set_parameter* or declare_parameter* methods. The callback takes a list of parameters that have been set successfully.

The callback can be valuable as a place to cause side effects based on parameter changes. For instance updating the internally tracked class attributes once the params have been changed successfully.

Parameters:

callback – The function that is called after parameters are set for the node.

add_pre_set_parameters_callback(callback: Callable[[List[Parameter[Any]]], List[Parameter[Any]]]) None

Add a callback gets triggered before parameters are validated.

Calling this function will add a callback in self._pre_set_parameter_callbacks list.

This callback can be used to modify the original list of parameters being set by the user. The modified list of parameters is then forwarded to the “on set parameter” callback for validation.

The callback takes a list of parameters to be set and returns a list of modified parameters.

One of the use case of “pre set callback” can be updating additional parameters conditioned on changes to a parameter.

All parameters in the modified list will be set atomically.

Note that the callback is only called while setting parameters with set_parameters, set_parameters_atomically, or externally with a parameters service.

The callback is not called when parameters are declared with declare_parameter or declare_parameters.

The callback is not called when parameters are undeclared with undeclare_parameter.

An empty modified parameter list from the callback will result in set_parameter* returning an unsuccessful result.

Parameters:

callback – The function that is called before parameters are validated.

add_waitable(waitable: Waitable[Any]) None

Add a class that is capable of adding things to the wait set.

Parameters:

waitable – An instance of a waitable that the node will add to the waitset.

property clients: Iterator[Client[Any, Any]]

Get clients that have been created on this node.

property context: Context

Get the context associated with the node.

count_clients(service_name: str) int

Return the number of clients on a given service.

service_name may be a relative, private, or fully qualified service name. A relative or private service is expanded using this node’s namespace and name. The queried service name is not remapped.

Parameters:

service_name – the service_name on which to count the number of clients.

Returns:

the number of clients on the service.

count_publishers(topic_name: str) int

Return the number of publishers on a given topic.

topic_name may be a relative, private, or fully qualified topic name. A relative or private topic is expanded using this node’s namespace and name. The queried topic name is not remapped.

Parameters:

topic_name – The topic name on which to count the number of publishers.

Returns:

The number of publishers on the topic.

count_services(service_name: str) int

Return the number of servers on a given service.

service_name may be a relative, private, or fully qualified service name. A relative or private service is expanded using this node’s namespace and name. The queried service name is not remapped.

Parameters:

service_name – the service_name on which to count the number of clients.

Returns:

the number of servers on the service.

count_subscribers(topic_name: str) int

Return the number of subscribers on a given topic.

topic_name may be a relative, private, or fully qualified topic name. A relative or private topic is expanded using this node’s namespace and name. The queried topic name is not remapped.

Parameters:

topic_name – The topic name on which to count the number of subscribers.

Returns:

The number of subscribers on the topic.

create_client(srv_type: Type[Srv[SrvRequestT, SrvResponseT]], srv_name: str, *, qos_profile: rclpy.qos.QoSProfile = rclpy.qos.qos_profile_services_default, callback_group: CallbackGroup | None = None) Client[SrvRequestT, SrvResponseT]

Create a new service client.

Parameters:
  • srv_type – The service type.

  • srv_name – The name of the service.

  • qos_profile – The quality of service profile to apply the service client.

  • callback_group – The callback group for the service client. If None, then the default callback group for the node is used.

create_guard_condition(callback: Callable[[], None], callback_group: CallbackGroup | None = None) GuardCondition

Create a new guard condition.

Warning

Users should call Node.destroy_guard_condition() to destroy the GuardCondition object.

create_publisher(msg_type: ~typing.Type[~rclpy.type_support.MsgT], topic: str, qos_profile: rclpy.qos.QoSProfile | int, *, callback_group: ~rclpy.callback_groups.CallbackGroup | None = None, event_callbacks: ~rclpy.event_handler.PublisherEventCallbacks | None = None, qos_overriding_options: ~rclpy.qos_overriding_options.QoSOverridingOptions | None = None, publisher_class: ~typing.Type[~rclpy.publisher.Publisher[~rclpy.type_support.MsgT]] = <class 'rclpy.publisher.Publisher'>) Publisher[MsgT]

Create a new publisher.

Parameters:
  • msg_type – The type of ROS messages the publisher will publish.

  • topic – The name of the topic the publisher will publish to.

  • qos_profile – A QoSProfile or a history depth to apply to the publisher. In the case that a history depth is provided, the QoS history is set to KEEP_LAST, the QoS history depth is set to the value of the parameter, and all other QoS settings are set to their default values.

  • callback_group – The callback group for the publisher’s event handlers. If None, then the default callback group for the node is used.

  • event_callbacks – User-defined callbacks for middleware events.

Returns:

The new publisher.

create_rate(frequency: float, clock: rclpy.clock.Clock | None = None) Rate

Create a Rate object.

Warning

Users should call Node.destroy_rate() to destroy the Rate object.

Parameters:
  • frequency – The frequency the Rate runs at (Hz).

  • clock – The clock the Rate gets time from.

create_service(srv_type: Type[Srv[SrvRequestT, SrvResponseT]], srv_name: str, callback: Callable[[SrvRequestT, SrvResponseT], SrvResponseT], *, qos_profile: rclpy.qos.QoSProfile = rclpy.qos.qos_profile_services_default, callback_group: CallbackGroup | None = None) Service[SrvRequestT, SrvResponseT]

Create a new service server.

Parameters:
  • srv_type – The service type.

  • srv_name – The name of the service.

  • callback – A user-defined callback function that is called when a service request received by the server.

  • qos_profile – The quality of service profile to apply the service server.

  • callback_group – The callback group for the service server. If None, then the default callback group for the node is used.

create_subscription(msg_type: Type[MsgT], topic: str, callback: Callable[[MsgT], None] | Callable[[MsgT, MessageInfo], None], qos_profile: rclpy.qos.QoSProfile | int, *, callback_group: CallbackGroup | None = None, event_callbacks: SubscriptionEventCallbacks | None = None, qos_overriding_options: QoSOverridingOptions | None = None, raw: bool = False) Subscription[MsgT]

Create a new subscription.

Parameters:
  • msg_type – The type of ROS messages the subscription will subscribe to.

  • topic – The name of the topic the subscription will subscribe to.

  • callback – A user-defined callback function that is called when a message is received by the subscription.

  • qos_profile – A QoSProfile or a history depth to apply to the subscription. In the case that a history depth is provided, the QoS history is set to KEEP_LAST, the QoS history depth is set to the value of the parameter, and all other QoS settings are set to their default values.

  • callback_group – The callback group for the subscription. If None, then the default callback group for the node is used.

  • event_callbacks – User-defined callbacks for middleware events.

  • raw – If True, then received messages will be stored in raw binary representation.

create_timer(timer_period_sec: float, callback: Callable[[], None] | Callable[[TimerInfo], None] | None, callback_group: CallbackGroup | None = None, clock: rclpy.clock.Clock | None = None, autostart: bool = True) Timer

Create a new timer.

If autostart is True (the default), the timer will be started and every timer_period_sec number of seconds the provided callback function will be called. If autostart is False, the timer will be created but not started; it can then be started by calling reset() on the timer object.

Parameters:
  • timer_period_sec – The period (in seconds) of the timer.

  • callback – A user-defined callback function that is called when the timer expires.

  • callback_group – The callback group for the timer. If None, then the default callback group for the node is used.

  • clock – The clock which the timer gets time from.

  • autostart – Whether to automatically start the timer after creation; defaults to True.

declare_parameter(name: str, value: AllowableParameterValueT | Type | rcl_interfaces.msg.ParameterValue, descriptor: rcl_interfaces.msg.ParameterDescriptor | None = None, ignore_override: bool = False) Parameter[AllowableParameterValueT]
declare_parameter(name: str, value: None = None, descriptor: None = None, ignore_override: bool = False) Parameter[Any]
declare_parameter(name: str, value: None | Type | rcl_interfaces.msg.ParameterValue = None, descriptor: rcl_interfaces.msg.ParameterDescriptor | None = None, ignore_override: bool = False) Parameter[Any]

Declare and initialize a parameter.

This method, if successful, will result in any callback registered with add_on_set_parameters_callback() and add_post_set_parameters_callback() to be called.

The name and type in the given descriptor is ignored, and should be specified using the name argument to this function and the default value’s type instead.

Parameters:
  • name – Fully-qualified name of the parameter, including its namespace.

  • value – Value of the parameter to declare.

  • descriptor – Descriptor for the parameter to declare.

  • ignore_override – True if overrides shall not be taken into account; False otherwise.

Returns:

Parameter with the effectively assigned value.

Raises:

ParameterAlreadyDeclaredException if the parameter had already been declared.

Raises:

InvalidParameterException if the parameter name is invalid.

Raises:

InvalidParameterValueException if the registered callback rejects the parameter.

declare_parameters(namespace: str, parameters: List[Tuple[str] | Tuple[str, Type] | Tuple[str, Any | Type | rcl_interfaces.msg.ParameterValue, rcl_interfaces.msg.ParameterDescriptor]], ignore_override: bool = False) List[Parameter[Any]]
declare_parameters(namespace: str, parameters: List[Tuple[str, Type] | Tuple[str, Any | Type | rcl_interfaces.msg.ParameterValue, rcl_interfaces.msg.ParameterDescriptor]], ignore_override: bool = False) List[Parameter[Any]]

Declare a list of parameters.

The tuples in the given parameter list shall contain the name for each parameter, optionally providing a value and a descriptor. The name and type in the given descriptors are ignored, and should be specified using the name argument to this function and the default value’s type instead. For each entry in the list, a parameter with a name of “namespace.name” will be declared. The resulting value for each declared parameter will be returned, considering parameter overrides set upon node creation as the first choice, or provided parameter values as the second one.

The name expansion is naive, so if you set the namespace to be “foo.”, then the resulting parameter names will be like “foo..name”. However, if the namespace is an empty string, then no leading ‘.’ will be placed before each name, which would have been the case when naively expanding “namespace.name”. This allows you to declare several parameters at once without a namespace.

This method will result in any callback registered with add_on_set_parameters_callback() and add_post_set_parameters_callback() to be called once for each parameter.

If a callback was registered previously with add_on_set_parameters_callback(), it will be called prior to setting the parameters for the node, once for each parameter. If one of the calls due to add_on_set_parameters_callback() fail, an exception will be raised and the remaining parameters will not be declared. Parameters declared up to that point will not be undeclared.

If a callback was registered previously with add_post_set_parameters_callback(), it will be called after setting the parameters successfully for the node, once for each parameter.

This method will not result in any callbacks registered with add_pre_set_parameters_callback() to be called.

Parameters:
  • namespace – Namespace for parameters.

  • parameters – List of tuples with parameters to declare.

  • ignore_override – True if overrides shall not be taken into account; False otherwise.

Returns:

Parameter list with the effectively assigned values for each of them.

Raises:

ParameterAlreadyDeclaredException if the parameter had already been declared.

Raises:

InvalidParameterException if the parameter name is invalid.

Raises:

InvalidParameterValueException if the registered callback rejects any parameter.

Raises:

TypeError if any tuple in parameters does not match the annotated type.

property default_callback_group: CallbackGroup

Get the default callback group.

If no other callback group is provided when the a ROS entity is created with the node, then it is added to the default callback group.

describe_parameter(name: str) rcl_interfaces.msg.ParameterDescriptor

Get the parameter descriptor of a given parameter.

Parameters:

name – Fully-qualified name of the parameter, including its namespace.

Returns:

ParameterDescriptor corresponding to the parameter, or default ParameterDescriptor if parameter had not been declared before and undeclared parameters are allowed.

Raises:

ParameterNotDeclaredException if parameter had not been declared before and undeclared parameters are not allowed.

describe_parameters(names: List[str]) List[rcl_interfaces.msg.ParameterDescriptor]

Get the parameter descriptors of a given list of parameters.

Parameters:

name – List of fully-qualified names of the parameters to describe.

Returns:

List of ParameterDescriptors corresponding to the given parameters. Default ParameterDescriptors shall be returned for parameters that had not been declared before if undeclared parameters are allowed.

Raises:

ParameterNotDeclaredException if at least one parameter had not been declared before and undeclared parameters are not allowed.

destroy_client(client: Client[Any, Any]) bool

Destroy a service client created by the node.

Returns:

True if successful, False otherwise.

destroy_guard_condition(guard: GuardCondition) bool

Destroy a guard condition created by the node.

Returns:

True if successful, False otherwise.

destroy_node() None

Destroy the node.

Frees resources used by the node, including any entities created by the following methods:

destroy_publisher(publisher: Publisher[Any]) bool

Destroy a publisher created by the node.

Returns:

True if successful, False otherwise.

destroy_rate(rate: Rate) bool

Destroy a Rate object created by the node.

Returns:

True if successful, False otherwise.

destroy_service(service: Service[Any, Any]) bool

Destroy a service server created by the node.

Returns:

True if successful, False otherwise.

destroy_subscription(subscription: Subscription[Any]) bool

Destroy a subscription created by the node.

Returns:

True if successful, False otherwise.

destroy_timer(timer: Timer) bool

Destroy a timer created by the node.

Returns:

True if successful, False otherwise.

property executor: Executor | None

Get the executor if the node has been added to one, else return None.

get_client_names_and_types_by_node(node_name: str, node_namespace: str) List[Tuple[str, List[str]]]

Get a list of discovered service clients for a remote node.

Parameters:
  • node_name – Name of a remote node to get service clients for.

  • node_namespace – Namespace of the remote node.

Returns:

List of tuples. The first element of each tuple is the service client name and the second element is a list of service client types.

Raises:
  • NodeNameNonExistentError – If the node wasn’t found.

  • RuntimeError – Unexpected failure.

get_clock() rclpy.clock.Clock

Get the clock used by the node.

get_fully_qualified_name() str

Get the node’s fully qualified name.

Returns:

Fully qualified node name.

get_fully_qualified_node_names() List[str]

Get a list of fully qualified names for discovered nodes.

Similar to get_node_names_namespaces(), but concatenates the names and namespaces.

Returns:

List of fully qualified node names.

get_logger() RcutilsLogger

Get the nodes logger.

get_name() str

Get the name of the node.

get_namespace() str

Get the namespace of the node.

get_node_names() List[str]

Get a list of names for discovered nodes.

Returns:

List of node names.

get_node_names_and_namespaces() List[Tuple[str, str]]

Get a list of names and namespaces for discovered nodes.

Returns:

List of tuples containing two strings: the node name and node namespace.

get_node_names_and_namespaces_with_enclaves() List[Tuple[str, str, str]]

Get a list of names, namespaces and enclaves for discovered nodes.

Returns:

List of tuples containing three strings: the node name, node namespace and enclave.

get_parameter(name: str) Parameter[Any]

Get a parameter by name.

Parameters:

name – Fully-qualified name of the parameter, including its namespace.

Returns:

The value for the given parameter name. A default Parameter will be returned for an undeclared parameter if undeclared parameters are allowed.

Raises:

ParameterNotDeclaredException if undeclared parameters are not allowed, and the parameter hadn’t been declared beforehand.

Raises:

ParameterUninitializedException if the parameter is statically typed and uninitialized.

get_parameter_or(name: str, alternative_value: Parameter[Any] | None = None) Parameter[Any]

Get a parameter or the alternative value.

If the alternative value is None, a default Parameter with the given name and NOT_SET type will be returned if the parameter was not declared.

Parameters:
  • name – Fully-qualified name of the parameter, including its namespace.

  • alternative_value – Alternative parameter to get if it had not been declared before.

Returns:

Requested parameter, or alternative value if it hadn’t been declared before or is an uninitialized statically typed parameter.

get_parameter_type(name: str) Type

Get a parameter type by name.

Parameters:

name – Fully-qualified name of the parameter, including its namespace.

Returns:

The type for the given parameter name. A default Parameter.Type.NOT_SET will be returned for an undeclared parameter if undeclared parameters are allowed.

Raises:

ParameterNotDeclaredException if undeclared parameters are not allowed, and the parameter hadn’t been declared beforehand.

get_parameter_types(names: List[str]) List[Type]

Get a list of parameter types.

Parameters:

names – Fully-qualified names of the parameters to get, including their namespaces.

Returns:

The values for the given parameter types. A default Parameter.Type.NOT_SET will be returned for undeclared parameters if undeclared parameters are allowed.

Raises:

ParameterNotDeclaredException if undeclared parameters are not allowed, and at least one parameter hadn’t been declared beforehand.

get_parameters(names: List[str]) List[Parameter[Any]]

Get a list of parameters.

Parameters:

names – Fully-qualified names of the parameters to get, including their namespaces.

Returns:

The values for the given parameter names. A default Parameter will be returned for undeclared parameters if undeclared parameters are allowed.

Raises:

ParameterNotDeclaredException if undeclared parameters are not allowed, and at least one parameter hadn’t been declared beforehand.

Raises:

ParameterUninitializedException if at least one parameter is statically typed and uninitialized.

get_parameters_by_prefix(prefix: str) Dict[str, Parameter[Any]]

Get parameters that have a given prefix in their names as a dictionary.

The names which are used as keys in the returned dictionary have the prefix removed. For example, if you use the prefix “foo” and the parameters “foo.ping”, “foo.pong” and “bar.baz” exist, then the returned dictionary will have the keys “ping” and “pong”. Note that the parameter separator is also removed from the parameter name to create the keys.

An empty string for the prefix will match all parameters.

If no parameters with the prefix are found, an empty dictionary will be returned.

Parameters:

prefix – The prefix of the parameters to get.

Returns:

Dict of parameters with the given prefix.

get_publisher_names_and_types_by_node(node_name: str, node_namespace: str, no_demangle: bool = False) List[Tuple[str, List[str]]]

Get a list of discovered topics for publishers of a remote node.

Parameters:
  • node_name – Name of a remote node to get publishers for.

  • node_namespace – Namespace of the remote node.

  • no_demangle – If True, then topic names and types returned will not be demangled.

Returns:

List of tuples. The first element of each tuple is the topic name and the second element is a list of topic types.

Raises:
  • NodeNameNonExistentError – If the node wasn’t found.

  • RuntimeError – Unexpected failure.

get_publishers_info_by_topic(topic_name: str, no_mangle: bool = False) List[TopicEndpointInfo]

Return a list of publishers on a given topic.

The returned parameter is a list of TopicEndpointInfo objects, where each will contain the node name, node namespace, topic type, topic endpoint’s GID, and its QoS profile.

When the no_mangle parameter is True, the provided topic_name should be a valid topic name for the middleware (useful when combining ROS with native middleware (e.g. DDS) apps). When the no_mangle parameter is False, the provided topic_name should follow ROS topic name conventions.

topic_name may be a relative, private, or fully qualified topic name. A relative or private topic will be expanded using this node’s namespace and name. The queried topic_name is not remapped.

Parameters:
  • topic_name – The topic_name on which to find the publishers.

  • no_mangle – If True, topic_name needs to be a valid middleware topic name, otherwise it should be a valid ROS topic name. Defaults to False.

Returns:

a list of TopicEndpointInfo for all the publishers on this topic.

get_service_names_and_types() List[Tuple[str, List[str]]]

Get a list of discovered service names and types.

Returns:

List of tuples. The first element of each tuple is the service name and the second element is a list of service types.

get_service_names_and_types_by_node(node_name: str, node_namespace: str) List[Tuple[str, List[str]]]

Get a list of discovered service servers for a remote node.

Parameters:
  • node_name – Name of a remote node to get services for.

  • node_namespace – Namespace of the remote node.

Returns:

List of tuples. The first element of each tuple is the service server name and the second element is a list of service types.

Raises:
  • NodeNameNonExistentError – If the node wasn’t found.

  • RuntimeError – Unexpected failure.

get_subscriber_names_and_types_by_node(node_name: str, node_namespace: str, no_demangle: bool = False) List[Tuple[str, List[str]]]

Get a list of discovered topics for subscriptions of a remote node.

Parameters:
  • node_name – Name of a remote node to get subscriptions for.

  • node_namespace – Namespace of the remote node.

  • no_demangle – If True, then topic names and types returned will not be demangled.

Returns:

List of tuples. The first element of each tuple is the topic name and the second element is a list of topic types.

Raises:
  • NodeNameNonExistentError – If the node wasn’t found.

  • RuntimeError – Unexpected failure.

get_subscriptions_info_by_topic(topic_name: str, no_mangle: bool = False) List[TopicEndpointInfo]

Return a list of subscriptions on a given topic.

The returned parameter is a list of TopicEndpointInfo objects, where each will contain the node name, node namespace, topic type, topic endpoint’s GID, and its QoS profile.

When the no_mangle parameter is True, the provided topic_name should be a valid topic name for the middleware (useful when combining ROS with native middleware (e.g. DDS) apps). When the no_mangle parameter is False, the provided topic_name should follow ROS topic name conventions.

topic_name may be a relative, private, or fully qualified topic name. A relative or private topic will be expanded using this node’s namespace and name. The queried topic_name is not remapped.

Parameters:
  • topic_name – The topic_name on which to find the subscriptions.

  • no_mangle – If True, topic_name needs to be a valid middleware topic name, otherwise it should be a valid ROS topic name. Defaults to False.

Returns:

A list of TopicEndpointInfo for all the subscriptions on this topic.

get_topic_names_and_types(no_demangle: bool = False) List[Tuple[str, List[str]]]

Get a list of discovered topic names and types.

Parameters:

no_demangle – If True, then topic names and types returned will not be demangled.

Returns:

List of tuples. The first element of each tuple is the topic name and the second element is a list of topic types.

property guards: Iterator[GuardCondition]

Get guards that have been created on this node.

property handle: rpyutils.import_c_library.Node

Get the handle to the underlying rcl_node_t.

Cannot be modified after node creation.

Raises:

AttributeError if modified after creation.

has_parameter(name: str) bool

Return True if parameter is declared; False otherwise.

list_parameters(prefixes: List[str], depth: int) rcl_interfaces.msg.ListParametersResult

Get a list of parameter names and their prefixes.

Parameters:
  • prefixes – A list of prefixes to filter the parameter names. Only the parameter names that start with any of the prefixes are returned. If empty, all parameter names are returned.

  • depth – The depth of nested parameter names to include.

Returns:

The list of parameter names and their prefixes.

Raises:

TypeError if the type of any of the passed arguments is not an expected type.

Raises:

ValueError if depth is a negative integer.

property publishers: Iterator[Publisher[Any]]

Get publishers that have been created on this node.

remove_on_set_parameters_callback(callback: Callable[[List[Parameter[Any]]], rcl_interfaces.msg.SetParametersResult]) None

Remove a callback from list of callbacks.

Calling this function will remove the callback from self._parameter_callbacks list.

Parameters:

callback – The function that is called whenever parameters are set for the node.

Raises:

ValueError if a callback is not present in the list of callbacks.

remove_post_set_parameters_callback(callback: Callable[[List[Parameter[Any]]], None]) None

Remove a callback from list of callbacks.

Calling this function will remove the callback from self._parameter_callbacks list.

Parameters:

callback – The function that is called whenever parameters are set for the node.

Raises:

ValueError if a callback is not present in the list of callbacks.

remove_pre_set_parameters_callback(callback: Callable[[List[Parameter[Any]]], List[Parameter[Any]]]) None

Remove a callback from list of callbacks.

Calling this function will remove the callback from self._pre_set_parameter_callbacks list.

Parameters:

callback – The function that is called whenever parameters are set for the node.

Raises:

ValueError if a callback is not present in the list of callbacks.

remove_waitable(waitable: Waitable[Any]) None

Remove a Waitable that was previously added to the node.

Parameters:

waitable – The Waitable to remove.

resolve_service_name(service: str, *, only_expand: bool = False) str

Return a service name expanded and remapped.

Parameters:
  • service – Service name to be expanded and remapped.

  • only_expand – If True, remapping rules won’t be applied.

Returns:

A fully qualified service name, the result of applying expansion and remapping to the given service.

resolve_topic_name(topic: str, *, only_expand: bool = False) str

Return a topic name expanded and remapped.

Parameters:
  • topic – Topic name to be expanded and remapped.

  • only_expand – If True, remapping rules won’t be applied.

Returns:

A fully qualified topic name, the result of applying expansion and remapping to the given topic.

property services: Iterator[Service[Any, Any]]

Get services that have been created on this node.

set_descriptor(name: str, descriptor: rcl_interfaces.msg.ParameterDescriptor, alternative_value: rcl_interfaces.msg.ParameterValue | None = None) rcl_interfaces.msg.ParameterValue

Set a new descriptor for a given parameter.

The name in the descriptor is ignored and set to name.

Parameters:
  • name – Fully-qualified name of the parameter to set the descriptor to.

  • descriptor – New descriptor to apply to the parameter.

  • alternative_value – Value to set to the parameter if the existing value does not comply with the new descriptor.

Returns:

ParameterValue for the given parameter name after applying the new descriptor.

Raises:

ParameterNotDeclaredException if parameter had not been declared before and undeclared parameters are not allowed.

Raises:

ParameterImmutableException if the parameter exists and is read-only.

Raises:

ParameterValueException if neither the existing value nor the alternative value complies with the provided descriptor.

set_parameters(parameter_list: List[Parameter[Any]]) List[rcl_interfaces.msg.SetParametersResult]

Set parameters for the node, and return the result for the set action.

If any parameter in the list was not declared beforehand and undeclared parameters are not allowed for the node, this method will raise a ParameterNotDeclaredException exception.

Parameters are set in the order they are declared in the list. If setting a parameter fails due to not being declared, then the parameters which have already been set will stay set, and no attempt will be made to set the parameters which come after.

If undeclared parameters are allowed, then all the parameters will be implicitly declared before being set even if they were not declared beforehand. Parameter overrides are ignored by this method.

This method will result in any callback registered with add_pre_set_parameters_callback(), add_on_set_parameters_callback() and add_post_set_parameters_callback() to be called once for each parameter.

If a callback was registered previously with add_pre_set_parameters_callback(), it will be called prior to the validation of parameters for the node, once for each parameter. If this callback makes modified parameter list empty, then it will be reflected in the returned result; no exceptions will be raised in this case.

If a callback was registered previously with add_on_set_parameters_callback(), it will be called prior to setting the parameters for the node, once for each parameter. If this callback prevents a parameter from being set, then it will be reflected in the returned result; no exceptions will be raised in this case.

If a callback was registered previously with add_post_set_parameters_callback(), it will be called after setting the parameters successfully for the node, once for each parameter.

For each successfully set parameter, a ParameterEvent message is published.

If the value type of the parameter is NOT_SET, and the existing parameter type is something else, then the parameter will be implicitly undeclared.

Parameters:

parameter_list – The list of parameters to set.

Returns:

The result for each set action as a list.

Raises:

ParameterNotDeclaredException if undeclared parameters are not allowed, and at least one parameter in the list hadn’t been declared beforehand.

set_parameters_atomically(parameter_list: List[Parameter[Any]]) rcl_interfaces.msg.SetParametersResult

Set the given parameters, all at one time, and then aggregate result.

If any parameter in the list was not declared beforehand and undeclared parameters are not allowed for the node, this method will raise a ParameterNotDeclaredException exception.

Parameters are set all at once. If setting a parameter fails due to not being declared, then no parameter will be set. Either all of the parameters are set or none of them are set.

If undeclared parameters are allowed for the node, then all the parameters will be implicitly declared before being set even if they were not declared beforehand.

This method will result in any callback registered with add_pre_set_parameters_callback() add_on_set_parameters_callback() and add_post_set_parameters_callback() to be called only once for all parameters.

If a callback was registered previously with add_pre_set_parameters_callback(), it will be called prior to the validation of node parameters only once for all parameters. If this callback makes modified parameter list empty, then it will be reflected in the returned result; no exceptions will be raised in this case.

If a callback was registered previously with add_on_set_parameters_callback(), it will be called prior to setting the parameters for the node only once for all parameters. If the callback prevents the parameters from being set, then it will be reflected in the returned result; no exceptions will be raised in this case.

If a callback was registered previously with add_post_set_parameters_callback(), it will be called after setting the node parameters successfully only once for all parameters.

For each successfully set parameter, a ParameterEvent message is published.

If the value type of the parameter is NOT_SET, and the existing parameter type is something else, then the parameter will be implicitly undeclared.

Parameters:

parameter_list – The list of parameters to set.

Returns:

Aggregate result of setting all the parameters atomically.

Raises:

ParameterNotDeclaredException if undeclared parameters are not allowed, and at least one parameter in the list hadn’t been declared beforehand.

property subscriptions: Iterator[Subscription[Any]]

Get subscriptions that have been created on this node.

property timers: Iterator[Timer]

Get timers that have been created on this node.

undeclare_parameter(name: str) None

Undeclare a previously declared parameter.

This method will not cause a callback registered with any of the add_pre_set_parameters_callback(), and add_post_set_parameters_callback() to be called.

Parameters:

name – Fully-qualified name of the parameter, including its namespace.

Raises:

ParameterNotDeclaredException if parameter had not been declared before.

Raises:

ParameterImmutableException if the parameter was created as read-only.

wait_for_node(fully_qualified_node_name: str, timeout: float) bool

Wait until node name is present in the system or timeout.

The node name should be the full name with namespace.

Parameters:
  • node_name – Fully qualified name of the node to wait for.

  • timeout – Seconds to wait for the node to be present. If negative, the function won’t timeout.

Returns:

True if the node was found, False if timeout.

property waitables: Iterator[Waitable[Any]]

Get waitables that have been created on this node.