2Partial stand-in of ROS2 `rclpy.parameter`.
4And some parameter-related classes from `rcl_interfaces.msg` for ROS1.
6Heavily modified copy from ROS2 `rclpy.parameter`,
7at https://github.com/ros2/rclpy (`rclpy/rclpy/parameter.py`),
8released under the Apache 2.0 License.
10------------------------------------------------------------------------------
11This file is part of rosros - simple unified interface to ROS1 / ROS2.
12Released under the BSD License.
17------------------------------------------------------------------------------
19## @namespace rosros.rclify.parameter
21# Original file copyright notice:
23# Copyright 2016 Open Source Robotics Foundation, Inc.
25# Licensed under the Apache License, Version 2.0 (the "License");
26# you may not use this file except in compliance with the License.
27# You may obtain a copy of the License at
29# http://www.apache.org/licenses/LICENSE-2.0
39PARAMETER_SEPARATOR_STRING =
"."
43 """ROS node parameter, a stand-in for ROS2 `rclpy.parameter.Parameter` in ROS1."""
46 """ROS parameter type, a stand-in for ROS2 `rclpy.parameter.Parameter.Type` in ROS1."""
64 @return a `
Parameter.Type` corresponding to the instance type of the given value
65 @throws `TypeError`
if the conversion to a type was
not possible
67 if isinstance(parameter_value, (list, tuple, array.array)):
68 for enumtype, valtype
in Parameter.ARRAYS.items():
69 if all(isinstance(v, valtype)
for v
in parameter_value):
71 raise TypeError(
"The given value is not a list of one of the allowed types.")
72 for enumtype, valtype
in Parameter.SCALARS.items():
73 if isinstance(parameter_value, valtype):
75 raise TypeError(
"The given value is not one of the allowed types.")
77 def check(self, parameter_value):
78 """Returns whether given value matches this type."""
79 if self
in Parameter.SCALARS:
80 return isinstance(parameter_value, Parameter.SCALARS[self])
81 if self
not in Parameter.ARRAYS \
82 or not isinstance(parameter_value, (list, tuple, array.array)):
85 return all(isinstance(v, bytes)
and len(v) == 1
for v
in parameter_value)
86 return all(isinstance(v, Parameter.ARRAYS[self])
for v
in parameter_value)
90 SCALARS = {Type.NOT_SET: type(
None), Type.BOOL: bool, Type.INTEGER: int,
91 Type.DOUBLE: float, Type.STRING: str}
94 ARRAYS = {Type.BYTE_ARRAY: bytes, Type.BOOL_ARRAY: bool, Type.INTEGER_ARRAY: int,
95 Type.DOUBLE_ARRAY: float, Type.STRING_ARRAY: str}
98 def __init__(self, name, type_=None, value=None):
99 """Raises error if unknown type or given value not of given type."""
101 type_ = Parameter.Type.from_parameter_value(value)
103 raise TypeError(
"Type must be an instance of %r" %
Parameter.Type)
104 if not type_.check(value):
105 raise ValueError(
"Type '%s' and value '%s' do not agree" % (type_, value))
124 """Returns `ParameterValue`."""
126 if Parameter.Type.BOOL == self.
_type_:
128 elif Parameter.Type.INTEGER == self.
_type_:
130 elif Parameter.Type.DOUBLE == self.
_type_:
131 parameter_value.double_value = self.
valuevalue
132 elif Parameter.Type.STRING == self.
_type_:
133 parameter_value.string_value = self.
valuevalue
134 elif Parameter.Type.BYTE_ARRAY == self.
_type_:
135 parameter_value.byte_array_value = self.
valuevalue
136 elif Parameter.Type.BOOL_ARRAY == self.
_type_:
137 parameter_value.bool_array_value = self.
valuevalue
138 elif Parameter.Type.INTEGER_ARRAY == self.
_type_:
139 parameter_value.integer_array_value = self.
valuevalue
140 elif Parameter.Type.DOUBLE_ARRAY == self.
_type_:
141 parameter_value.double_array_value = self.
valuevalue
142 elif Parameter.Type.STRING_ARRAY == self.
_type_:
143 parameter_value.string_array_value = self.
valuevalue
144 return parameter_value
151 Used to determine which of the next *_value fields are set.
152 `Parameter.Type.NOT_SET` indicates that the parameter was not set
153 (
if gotten)
or is uninitialized.
155 Stand-
in for ROS2 `rcl_interfaces.msg.ParameterValue`
in ROS1.
157 def __init__(self, type=0, bool_value=False, integer_value=0, double_value=0.0, string_value="",
158 byte_array_value=None, bool_array_value=None, integer_array_value=None,
159 double_array_value=None, string_array_value=None):
182 """Returns raw value according to type."""
185 if Parameter.Type.BOOL == type_:
187 elif Parameter.Type.INTEGER == type_:
189 elif Parameter.Type.DOUBLE == type_:
191 elif Parameter.Type.STRING == type_:
193 elif Parameter.Type.BYTE_ARRAY == type_:
195 elif Parameter.Type.BOOL_ARRAY == type_:
197 elif Parameter.Type.INTEGER_ARRAY == type_:
199 elif Parameter.Type.DOUBLE_ARRAY == type_:
201 elif Parameter.Type.STRING_ARRAY == type_:
208 This is the message to communicate a parameter
's descriptor.
210 Stand-in for ROS2 `rcl_interfaces.msg.ParameterDescriptor`
in ROS1.
213 def __init__(self, name="", type=0, description="", additional_constraints="", read_only=False,
214 dynamic_typing=False, floating_point_range=None, integer_range=None):
216 self.name = name
or ""
218 self.
type = type
or 0
240 This is the message to communicate the result of setting parameters.
242 Stand-
in for ROS2 `rcl_interfaces.msg.SetParametersResult`
in ROS1.
245 def __init__(self, successful=False, reason=""):
248 self.successful = successful
or False
256 Represents bounds and a step value
for a floating point typed parameter.
258 Stand-
in for ROS2 `rcl_interfaces.msg.FloatingPointRange`
in ROS1.
260 def __init__(self, from_value=0.0, to_value=0.0, step=0.0):
262 self.from_value = from_value
or 0.0
264 self.to_value = to_value
or 0.0
283 self.
step = step
or 0.0
288 Represents bounds and a step value
for an integer typed parameter.
290 Stand-
in for ROS2 `rcl_interfaces.msg.IntegerRange`
in ROS1.
292 def __init__(self, from_value=0, to_value=0, step=0):
312 self.
step = step
or 0
316 "PARAMETER_SEPARATOR_STRING",
"Parameter",
"ParameterValue",
"ParameterDescriptor",
317 "SetParametersResult",
"FloatingPointRange",
"IntegerRange",
Represents bounds and a step value for a floating point typed parameter.
__init__(self, from_value=0.0, to_value=0.0, step=0.0)
Ideally, the step would be less than or equal to the distance between the bounds, as well as an even ...
to_value
End value for valid values, inclusive.
step
Size of valid steps between the from and to bound.
from_value
Start value for valid values, inclusive.
Represents bounds and a step value for an integer typed parameter.
step
Size of valid steps between the from and to bound.
ROS parameter type, a stand-in for ROS2 `rclpy.parameter.Parameter.Type` in ROS1.
from_parameter_value(cls, parameter_value)
Returns `Parameter.Type` for given value.
check(self, parameter_value)
Returns whether given value matches this type.
This is the message to communicate a parameter's descriptor.
dynamic_typing
If true, the parameter is allowed to change type.
read_only
If 'true' then the value cannot change after it has been initialized.
description
Description of the parameter, visible from introspection tools.
floating_point_range
FloatingPointRange consists of a from_value, a to_value, and a step.
__init__(self, name="", type=0, description="", additional_constraints="", read_only=False, dynamic_typing=False, floating_point_range=None, integer_range=None)
additional_constraints
Plain English description of additional constraints which cannot be expressed with the available cons...
integer_range
IntegerRange consists of a from_value, a to_value, and a step.
type
Enum values are defined in `Parameter.Type`.
ROS node parameter, a stand-in for ROS2 `rclpy.parameter.Parameter` in ROS1.
__init__(self, name, type_=None, value=None)
Raises error if unknown type or given value not of given type.
get_parameter_value(self)
Returns `ParameterValue`.
string_array_value
An array of string values.
bool_value
Boolean value, can be either true or false.
string_value
A textual value with no practical length limit.
integer_value
Integer value.
byte_array_value
An array of bytes, used for non-textual information.
type
The type of this parameter, which corresponds to the appropriate field below.
bool_array_value
An array of boolean values.
integer_array_value
An array of 64-bit integer values.
__init__(self, type=0, bool_value=False, integer_value=0, double_value=0.0, string_value="", byte_array_value=None, bool_array_value=None, integer_array_value=None, double_array_value=None, string_array_value=None)
double_array_value
An array of 64-bit floating point values.
get_value(self)
Returns raw value according to type.
double_value
A double precision floating point value.
This is the message to communicate the result of setting parameters.
reason
Reason why the setting was either successful or a failure.
__init__(self, successful=False, reason="")