Parameters

Parameter

class rclpy.parameter.Parameter(name: str, type_: Type | None = None, value: None = None)
class rclpy.parameter.Parameter(name: str, type_: Type, value: AllowableParameterValueT)
class rclpy.parameter.Parameter(name: str, *, value: AllowableParameterValueT)
class Type(value, names=<not given>, *values, module=None, qualname=None, type=None, start=1, boundary=None)
check(parameter_value: Any) bool
classmethod from_parameter_value(parameter_value: Any) Type

Get a Parameter.Type from a given variable.

Returns:

A Parameter.Type corresponding to the instance type of the given value.

Raises:

TypeError if the conversion to a type was not possible.

classmethod from_parameter_msg(param_msg: rcl_interfaces.msg.Parameter) Parameter[Any]
get_parameter_value() rcl_interfaces.msg.ParameterValue
property name: str
to_parameter_msg() rcl_interfaces.msg.Parameter
property type_: Type
property value: AllowableParameterValueT
rclpy.parameter.get_parameter_value(string_value: str) rcl_interfaces.msg.ParameterValue

Guess the desired type of the parameter based on the string value.

Parameters:

string_value – The string value to be converted to a ParameterValue.

Returns:

The ParameterValue.

rclpy.parameter.parameter_dict_from_yaml_file(parameter_file: str, use_wildcard: bool = False, target_nodes: List[str] | None = None, namespace: str = '') Dict[str, rcl_interfaces.msg.Parameter]

Build a dict of parameters from a YAML file.

Will load all parameters if target_nodes is None or empty.

Raises:
  • RuntimeError – if a target node is not in the file

  • RuntimeError – if the is not a valid ROS parameter file

Parameters:
  • parameter_file – Path to the YAML file to load parameters from.

  • use_wildcard – Use wildcard matching for the target nodes.

  • target_nodes – List of nodes in the YAML file to load parameters from.

  • namespace – Namespace to prepend to all parameters.

Returns:

A dict of Parameter messages keyed by the parameter names

rclpy.parameter.parameter_value_to_python(parameter_value: rcl_interfaces.msg.ParameterValue) Any

Get the value for the Python builtin type from a rcl_interfaces/msg/ParameterValue object.

Returns the value member of the message based on the type member. Returns None if the parameter is “NOT_SET”.

Parameters:

parameter_value – The message to get the value from.

Raises:

RuntimeError – if the member type has an unexpected value.

Parameter Service

class rclpy.parameter_service.ParameterService(node: Node)

Parameter Client

class rclpy.parameter_client.AsyncParameterClient(node: Node, remote_node_name: str, qos_profile: rclpy.qos.QoSProfile = rclpy.qos.qos_profile_services_default, callback_group: CallbackGroup | None = None)

Create an AsyncParameterClient.

An AsyncParameterClient that uses services offered by a remote node to query and modify parameters in a streamlined way.

Usage example:

import rclpy
from rclpy.parameter import Parameter
node = rclpy.create_node('my_node')

client = AsyncParameterClient(node, 'example_node')

# set parameters on example node
future = client.set_parameters([
    Parameter('int_param', Parameter.Type.INTEGER, 88),
    Parameter('string/param', Parameter.Type.STRING, 'hello world').to_parameter_msg(),
])
self.executor.spin_until_future_complete(future)
results = future.result()  # rcl_interfaces.srv.SetParameters.Response

For more on service names, see: ROS 2 docs.

Parameters:
  • node – Node used to create clients that will interact with the remote node

  • remote_node_name – Name of remote node for which the parameters will be managed

delete_parameters(names: List[str], callback: Callable[[rcl_interfaces.srv.SetParameters.Response], None] | None = None) Future[rcl_interfaces.srv.SetParameters.Response]

Unset parameters with given names.

The result after the returned future is complete will be of type rcl_interfaces.srv.SetParameters.Response.

Note: Only parameters that have been declared as dynamically typed can be unset.

Parameters:
  • names – List of parameter names to unset.

  • callback – Callback function to call when the request is complete.

Returns:

Future with the result of the request.

describe_parameters(names: List[str], callback: Callable[[rcl_interfaces.srv.DescribeParameters.Response], None] | None = None) Future[rcl_interfaces.srv.DescribeParameters.Response]

Describe parameters given names.

The result after the returned future is complete will be of type rcl_interfaces.srv.DescribeParameters.Response.

Parameters:
  • names – List of parameter names to describe

  • callback – Callback function to call when the request is complete.

Returns:

Future with the result of the request.

get_parameter_types(names: List[str], callback: Callable[[rcl_interfaces.srv.GetParameterTypes.Response], None] | None = None) Future[rcl_interfaces.srv.GetParameterTypes.Response]

Get parameter types given names.

The result after the returned future is complete will be of type rcl_interfaces.srv.GetParameterTypes.Response.

Parameter type definitions are given in Parameter.Type

Parameters:
  • names – List of parameter names to get types for.

  • callback – Callback function to call when the request is complete.

Returns:

Future with the result of the request.

get_parameters(names: List[str], callback: Callable[[rcl_interfaces.srv.GetParameters.Response], None] | None = None) Future[rcl_interfaces.srv.GetParameters.Response]

Get parameters given names.

Parameters:
  • names – List of parameter names to get.

  • callback – Callback function to call when the request is complete.

Returns:

Future with the result of the request.

list_parameters(prefixes: List[str] | None = None, depth: int | None = None, callback: Callable[[rcl_interfaces.srv.ListParameters.Response], None] | None = None) Future[rcl_interfaces.srv.ListParameters.Response]

List all parameters with given prefixes.

Parameters:
  • prefixes – List of prefixes to filter by.

  • depth – Depth of the parameter tree to list. None means unlimited.

  • callback – Callback function to call when the request is complete.

Returns:

Future with the result of the request.

load_parameter_file(parameter_file: str, use_wildcard: bool = False, callback: Callable[[rcl_interfaces.srv.SetParameters.Response], None] | None = None) Future[rcl_interfaces.srv.SetParameters.Response]

Load parameters from a yaml file.

Wrapper around rclpy.parameter.parameter_dict_from_yaml_file.

The result after the returned future is complete will be of type rcl_interfaces.srv.SetParameters.Response.

Parameters:
  • parameter_file – Path to the parameter file.

  • use_wildcard – Whether to use wildcard expansion.

Returns:

Future with the result from the set_parameters call.

load_parameter_file_atomically(parameter_file: str, use_wildcard: bool = False, callback: Callable[[rcl_interfaces.srv.SetParameters.Response], None] | None = None) Future[rcl_interfaces.srv.SetParameters.Response]

Load parameters from a yaml file atomically.

Wrapper around rclpy.parameter.parameter_dict_from_yaml_file.

The result after the returned future is complete will be of type rcl_interfaces.srv.SetParameters.Response.

Parameters:
  • parameter_file – Path to the parameter file.

  • use_wildcard – Whether to use wildcard expansion.

Returns:

Future with the result from the set_parameters_atomically call.

on_parameter_event(callback: Callable[[rcl_interfaces.msg.ParameterEvent], None] | Callable[[rcl_interfaces.msg.ParameterEvent, MessageInfo], None], qos_profile: rclpy.qos.QoSProfile = rclpy.qos.qos_profile_parameter_events, *, callback_group: CallbackGroup | None = None, event_callbacks: SubscriptionEventCallbacks | None = None, qos_overriding_options: QoSOverridingOptions | None = None, raw: bool = False) Subscription[rcl_interfaces.msg.ParameterEvent]
services_are_ready() bool

Check if all services are ready.

Returns:

True if all services are available, False otherwise.

set_parameters(parameters: Sequence[Parameter[Any] | rcl_interfaces.msg.Parameter], callback: Callable[[rcl_interfaces.srv.SetParameters.Response], None] | None = None) Future[rcl_interfaces.srv.SetParameters.Response]

Set parameters given a list of parameters.

The result after the returned future is complete will be of type rcl_interfaces.srv.SetParameters.Response.

Parameters:
  • parameters – Sequence of parameters to set.

  • callback – Callback function to call when the request is complete.

Returns:

Future with the result of the request.

set_parameters_atomically(parameters: Sequence[Parameter[Any] | rcl_interfaces.msg.Parameter], callback: Callable[[rcl_interfaces.srv.SetParametersAtomically.Response], None] | None = None) Future[rcl_interfaces.srv.SetParametersAtomically.Response]

Set parameters atomically.

The result after the returned future is complete will be of type rcl_interfaces.srv.SetParametersAtomically.Response.

Parameters:
  • parameters – Sequence of parameters to set.

  • callback – Callback function to call when the request is complete.

Returns:

Future with the result of the request.

wait_for_services(timeout_sec: float | None = None) bool

Wait for all parameter services to be available.

Parameters:

timeout_sec – Seconds to wait. If None, then wait forever.

Returns:

True if all services becomes available, False otherwise.