Parameters
Parameter
- class rclpy.parameter.Parameter(name: str, type_: Type | 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: AllowableParameterValueT) bool
- classmethod from_parameter_msg(param_msg: rcl_interfaces.msg.Parameter) Parameter[AllowableParameterValueT]
- get_parameter_value() rcl_interfaces.msg.ParameterValue
- property name: str
- to_parameter_msg() rcl_interfaces.msg.Parameter
- 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. ReturnsNone
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)