-
Notifications
You must be signed in to change notification settings - Fork 481
Add ParameterDescriptor override from yaml #909
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
base: rolling
Are you sure you want to change the base?
Changes from all commits
702cf7f
22b897a
aaa8f73
8965a81
2727fdc
e59690b
f66c785
e6546c8
070abdd
ff1b8e5
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
| Original file line number | Diff line number | Diff line change |
|---|---|---|
|
|
@@ -102,13 +102,14 @@ NodeParameters::NodeParameters( | |
| // If asked, initialize any parameters that ended up in the initial parameter values, | ||
| // but did not get declared explcitily by this point. | ||
| if (automatically_declare_parameters_from_overrides) { | ||
| rcl_interfaces::msg::ParameterDescriptor descriptor; | ||
| descriptor.dynamic_typing = true; | ||
|
||
| for (const auto & pair : this->get_parameter_overrides()) { | ||
| if (!this->has_parameter(pair.first)) { | ||
| rcl_interfaces::msg::ParameterDescriptor descriptor; | ||
| descriptor = pair.second.descriptor; | ||
| descriptor.dynamic_typing = true; | ||
| this->declare_parameter( | ||
| pair.first, | ||
| pair.second, | ||
| pair.second.value, | ||
| descriptor, | ||
| true); | ||
| } | ||
|
|
@@ -332,7 +333,7 @@ __declare_parameter_common( | |
| const rclcpp::ParameterValue & default_value, | ||
| const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor, | ||
| std::map<std::string, rclcpp::node_interfaces::ParameterInfo> & parameters_out, | ||
| const std::map<std::string, rclcpp::ParameterValue> & overrides, | ||
| const std::map<std::string, rclcpp::node_interfaces::ParameterInfo> & overrides, | ||
| CallbacksContainerType & callback_container, | ||
| const OnParametersSetCallbackType & callback, | ||
| rcl_interfaces::msg::ParameterEvent * parameter_event_out, | ||
|
|
@@ -345,8 +346,19 @@ __declare_parameter_common( | |
| // Use the value from the overrides if available, otherwise use the default. | ||
| const rclcpp::ParameterValue * initial_value = &default_value; | ||
| auto overrides_it = overrides.find(name); | ||
|
|
||
| // If override for parameter value, use it | ||
| // If parameter override only, don't override descriptor | ||
| // If override for descriptor, use it | ||
| // If descriptor override only, don't override parameter value | ||
|
|
||
| if (!ignore_override && overrides_it != overrides.end()) { | ||
| initial_value = &overrides_it->second; | ||
| if (overrides_it->second.value.get_type() != rclcpp::ParameterType::PARAMETER_NOT_SET) { | ||
| initial_value = &overrides_it->second.value; | ||
| } | ||
| if (overrides_it->second.descriptor.name != "") { | ||
| parameter_infos[name].descriptor = overrides_it->second.descriptor; | ||
| } | ||
| } | ||
|
|
||
| // If there is no initial value, then skip initialization | ||
|
|
@@ -397,7 +409,7 @@ declare_parameter_helper( | |
| rcl_interfaces::msg::ParameterDescriptor parameter_descriptor, | ||
| bool ignore_override, | ||
| std::map<std::string, rclcpp::node_interfaces::ParameterInfo> & parameters, | ||
| const std::map<std::string, rclcpp::ParameterValue> & overrides, | ||
| const std::map<std::string, rclcpp::node_interfaces::ParameterInfo> & overrides, | ||
| CallbacksContainerType & callback_container, | ||
| const OnParametersSetCallbackType & callback, | ||
| rclcpp::Publisher<rcl_interfaces::msg::ParameterEvent> * events_publisher, | ||
|
|
@@ -1002,7 +1014,7 @@ NodeParameters::add_on_set_parameters_callback(OnParametersSetCallbackType callb | |
| return handle; | ||
| } | ||
|
|
||
| const std::map<std::string, rclcpp::ParameterValue> & | ||
| const std::map<std::string, rclcpp::node_interfaces::ParameterInfo> & | ||
| NodeParameters::get_parameter_overrides() const | ||
| { | ||
| return parameter_overrides_; | ||
|
|
||
| Original file line number | Diff line number | Diff line change |
|---|---|---|
|
|
@@ -12,6 +12,7 @@ | |
| // See the License for the specific language governing permissions and | ||
| // limitations under the License. | ||
|
|
||
| #include <limits> | ||
| #include <string> | ||
| #include <vector> | ||
|
|
||
|
|
@@ -21,6 +22,9 @@ using rclcpp::exceptions::InvalidParametersException; | |
| using rclcpp::exceptions::InvalidParameterValueException; | ||
| using rclcpp::ParameterMap; | ||
| using rclcpp::ParameterValue; | ||
| using rcl_interfaces::msg::ParameterDescriptor; | ||
| using rcl_interfaces::msg::FloatingPointRange; | ||
| using rcl_interfaces::msg::IntegerRange; | ||
|
|
||
| ParameterMap | ||
| rclcpp::parameter_map_from(const rcl_params_t * const c_params) | ||
|
|
@@ -49,11 +53,9 @@ rclcpp::parameter_map_from(const rcl_params_t * const c_params) | |
| node_name = c_node_name; | ||
| } | ||
|
|
||
| const rcl_node_params_t * const c_params_node = &(c_params->params[n]); | ||
|
|
||
| std::vector<Parameter> & params_node = parameters[node_name]; | ||
| params_node.reserve(c_params_node->num_params); | ||
| ParameterAndDescriptor & params = parameters[node_name]; | ||
|
|
||
| const rcl_node_params_t * const c_params_node = &(c_params->params[n]); | ||
| for (size_t p = 0; p < c_params_node->num_params; ++p) { | ||
| const char * const c_param_name = c_params_node->parameter_names[p]; | ||
| if (NULL == c_param_name) { | ||
|
|
@@ -62,7 +64,21 @@ rclcpp::parameter_map_from(const rcl_params_t * const c_params) | |
| throw InvalidParametersException(message); | ||
| } | ||
| const rcl_variant_t * const c_param_value = &(c_params_node->parameter_values[p]); | ||
| params_node.emplace_back(c_param_name, parameter_value_from(c_param_value)); | ||
| params[c_param_name].value = parameter_value_from(c_param_value); | ||
| } | ||
|
|
||
| const rcl_node_params_descriptors_t * const c_param_descriptors_node = | ||
| &(c_params->descriptors[n]); | ||
| for (size_t p = 0; p < c_param_descriptors_node->num_descriptors; ++p) { | ||
| const char * const c_param_name = c_param_descriptors_node->parameter_names[p]; | ||
| if (NULL == c_param_name) { | ||
| std::string message( | ||
| "At node " + std::to_string(n) + " parameter " + std::to_string(p) + " name is NULL"); | ||
|
Contributor
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. @bpwilcox do we need an auxiliary variable?
Contributor
Author
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. The |
||
| throw InvalidParametersException(message); | ||
| } | ||
| const rcl_param_descriptor_t * const c_param_descriptor = | ||
| &(c_param_descriptors_node->parameter_descriptors[p]); | ||
| params[c_param_name].descriptor = parameter_descriptor_from(c_param_name, c_param_descriptor); | ||
| } | ||
| } | ||
| return parameters; | ||
|
|
@@ -127,6 +143,85 @@ rclcpp::parameter_value_from(const rcl_variant_t * const c_param_value) | |
| throw InvalidParameterValueException("No parameter value set"); | ||
| } | ||
|
|
||
| ParameterDescriptor | ||
| rclcpp::parameter_descriptor_from( | ||
| const char * const name, | ||
| const rcl_param_descriptor_t * const c_param_descriptor) | ||
| { | ||
| if (NULL == c_param_descriptor) { | ||
| throw InvalidParameterValueException("Passed argument is NULL"); | ||
| } | ||
| ParameterDescriptor p; | ||
|
|
||
| if (name) { | ||
| p.name = std::string(name); | ||
| } | ||
| if (c_param_descriptor->type) { | ||
| p.type = *(c_param_descriptor->type); | ||
| } | ||
| if (c_param_descriptor->description) { | ||
| p.description = std::string(c_param_descriptor->description); | ||
| } | ||
| if (c_param_descriptor->additional_constraints) { | ||
| p.additional_constraints = std::string(c_param_descriptor->additional_constraints); | ||
| } | ||
| if (c_param_descriptor->read_only) { | ||
| p.read_only = *(c_param_descriptor->read_only); | ||
| } | ||
|
|
||
| if (c_param_descriptor->dynamic_typing) { | ||
| p.dynamic_typing = *(c_param_descriptor->dynamic_typing); | ||
| } | ||
|
|
||
| if (c_param_descriptor->min_value_int || c_param_descriptor->max_value_int || | ||
| c_param_descriptor->step_int) | ||
| { | ||
| if (c_param_descriptor->min_value_double || c_param_descriptor->max_value_double || | ||
| c_param_descriptor->step_double) | ||
| { | ||
| throw InvalidParameterValueException( | ||
| "Mixed 'integer' and 'double' types not supported for parameter descriptor range"); | ||
| } | ||
| IntegerRange i; | ||
| if (c_param_descriptor->min_value_int) { | ||
| i.from_value = *(c_param_descriptor->min_value_int); | ||
| } else { | ||
| i.from_value = std::numeric_limits<int64_t>::min(); | ||
| } | ||
| if (c_param_descriptor->max_value_int) { | ||
| i.to_value = *(c_param_descriptor->max_value_int); | ||
| } else { | ||
| i.to_value = std::numeric_limits<int64_t>::max(); | ||
| } | ||
| if (c_param_descriptor->step_int) { | ||
| i.step = *(c_param_descriptor->step_int); | ||
| } | ||
| p.integer_range.push_back(i); | ||
| } else if ( // NOLINT | ||
| c_param_descriptor->min_value_double || | ||
| c_param_descriptor->max_value_double || | ||
| c_param_descriptor->step_double) | ||
hidmic marked this conversation as resolved.
Show resolved
Hide resolved
|
||
| { | ||
| FloatingPointRange f; | ||
| if (c_param_descriptor->min_value_double) { | ||
| f.from_value = *(c_param_descriptor->min_value_double); | ||
| } else { | ||
| f.from_value = std::numeric_limits<double>::lowest(); | ||
| } | ||
| if (c_param_descriptor->max_value_double) { | ||
| f.to_value = *(c_param_descriptor->max_value_double); | ||
| } else { | ||
| f.to_value = std::numeric_limits<double>::max(); | ||
| } | ||
| if (c_param_descriptor->step_double) { | ||
| f.step = *(c_param_descriptor->step_double); | ||
| } | ||
| p.floating_point_range.push_back(f); | ||
| } | ||
|
|
||
| return p; | ||
| } | ||
|
|
||
| ParameterMap | ||
| rclcpp::parameter_map_from_yaml_file(const std::string & yaml_filename) | ||
| { | ||
|
|
||
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
@bpwilcox meta: hmm, why not pushing this
descriptorattribute intorclcpp::Parameter? Then we can userclcpp::Parametereverywhere.There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I do agree that you could put the descriptor in the
rclcpp::Parameterobject, however that seems to be a more far-reaching change than this PR, especially since many user-code usesrclcpp::Parameter. I think it is a good candidate for a follow-up PR.