-
Notifications
You must be signed in to change notification settings - Fork 479
Parameter service compliance #2515
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 2 commits
9bd5769
dfd40a2
1f8620a
5db9ffa
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 |
|---|---|---|
|
|
@@ -41,15 +41,11 @@ ParameterService::ParameterService( | |
| const std::shared_ptr<rcl_interfaces::srv::GetParameters::Request> request, | ||
| std::shared_ptr<rcl_interfaces::srv::GetParameters::Response> response) | ||
| { | ||
| try { | ||
| auto parameters = node_params->get_parameters(request->names); | ||
| for (const auto & param : parameters) { | ||
| response->values.push_back(param.get_value_message()); | ||
| } | ||
| } catch (const rclcpp::exceptions::ParameterNotDeclaredException & ex) { | ||
| RCLCPP_DEBUG(rclcpp::get_logger("rclcpp"), "Failed to get parameters: %s", ex.what()); | ||
| } catch (const rclcpp::exceptions::ParameterUninitializedException & ex) { | ||
| RCLCPP_DEBUG(rclcpp::get_logger("rclcpp"), "Failed to get parameters: %s", ex.what()); | ||
| response->values.reserve(request->names.size()); | ||
| for (const auto & name : request->names) { | ||
| rclcpp::Parameter value; | ||
| node_params->get_parameter(name, value); | ||
| response->values.push_back(value.get_value_message()); | ||
| } | ||
| }, | ||
| qos_profile, nullptr); | ||
|
|
@@ -62,15 +58,11 @@ ParameterService::ParameterService( | |
| const std::shared_ptr<rcl_interfaces::srv::GetParameterTypes::Request> request, | ||
| std::shared_ptr<rcl_interfaces::srv::GetParameterTypes::Response> response) | ||
| { | ||
| try { | ||
| auto types = node_params->get_parameter_types(request->names); | ||
| std::transform( | ||
| types.cbegin(), types.cend(), | ||
| std::back_inserter(response->types), [](const uint8_t & type) { | ||
| return static_cast<rclcpp::ParameterType>(type); | ||
| }); | ||
| } catch (const rclcpp::exceptions::ParameterNotDeclaredException & ex) { | ||
| RCLCPP_DEBUG(rclcpp::get_logger("rclcpp"), "Failed to get parameter types: %s", ex.what()); | ||
| response->types.reserve(request->names.size()); | ||
| for (const auto & name : request->names) { | ||
| rclcpp::Parameter value; | ||
| node_params->get_parameter(name, value); | ||
| response->types.push_back(value.get_type()); | ||
| } | ||
| }, | ||
| qos_profile, nullptr); | ||
|
|
@@ -93,7 +85,7 @@ ParameterService::ParameterService( | |
| } catch (const rclcpp::exceptions::ParameterNotDeclaredException & ex) { | ||
| RCLCPP_DEBUG(rclcpp::get_logger("rclcpp"), "Failed to set parameter: %s", ex.what()); | ||
| result.successful = false; | ||
| result.reason = ex.what(); | ||
| result.reason = "Parameter is not declared by the node, which only allows declared parameters"; | ||
| } | ||
| response->results.push_back(result); | ||
| } | ||
|
|
@@ -135,11 +127,28 @@ ParameterService::ParameterService( | |
| const std::shared_ptr<rcl_interfaces::srv::DescribeParameters::Request> request, | ||
| std::shared_ptr<rcl_interfaces::srv::DescribeParameters::Response> response) | ||
| { | ||
| try { | ||
| auto descriptors = node_params->describe_parameters(request->names); | ||
| response->descriptors = descriptors; | ||
| } catch (const rclcpp::exceptions::ParameterNotDeclaredException & ex) { | ||
| RCLCPP_DEBUG(rclcpp::get_logger("rclcpp"), "Failed to describe parameters: %s", ex.what()); | ||
| // TODO(@mxgrey): This could have fewer heap allocations if | ||
| // NodeParametersInterface had a singular describe_parameter function or | ||
| // if describe_parameters could accept an argument to behave as if | ||
| // allow_undeclared_ is true. | ||
| for (const auto & name : request->names) { | ||
| bool description_found = false; | ||
| try { | ||
| auto description = node_params->describe_parameters({name}); | ||
| if (!description.empty()) { | ||
| description_found = true; | ||
| response->descriptors.push_back(std::move(description.front())); | ||
| } | ||
| } catch (const rclcpp::exceptions::ParameterNotDeclaredException & ex) { | ||
| // If the parameter was not declared then we will just push_back a | ||
| // default-initialized descriptor. | ||
| } | ||
|
|
||
| if (!description_found) { | ||
| auto default_description = rcl_interfaces::msg::ParameterDescriptor(); | ||
| default_description.name = name; | ||
| response->descriptors.push_back(default_description); | ||
|
Comment on lines
+148
to
+150
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. Can we not move these lined in to 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. We could use In general I think exceptions are a rather blunt instrument so I prefer to avoid using them whenever possible. We could avoid exceptions if we are willing to make one of the following tweaks to (1) Add a new argument to or (2) have a function that gets parameter descriptions one at a time, returning I don't have a strong opinion about which is better... Option (1) would make it easy to avoid any code duplication, but the argument is awkward, and I can't think of a name for it that wouldn't be confusing. Option (2) is probably the cleanest from an API standpoint, but then we have to consider the mutex locking situation. The natural thing to do would be to reimplement 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. I guess a third option would be to reimplement |
||
| } | ||
| } | ||
| }, | ||
| qos_profile, nullptr); | ||
|
|
||
Uh oh!
There was an error while loading. Please reload this page.