-
Notifications
You must be signed in to change notification settings - Fork 522
Description
This is the code that declares the parameter start_type_description_service.
It uses a try/catch idiom, but does not catches ParameterAlreadyDeclaredException.
rclcpp/rclcpp/src/rclcpp/node_interfaces/node_type_descriptions.cpp
Lines 70 to 84 in 7ebc9e4
| bool enabled = false; | |
| try { | |
| auto enable_param = node_parameters->declare_parameter( | |
| enable_param_name, | |
| rclcpp::ParameterValue(true), | |
| rcl_interfaces::msg::ParameterDescriptor() | |
| .set__name(enable_param_name) | |
| .set__type(rclcpp::PARAMETER_BOOL) | |
| .set__description("Start the ~/get_type_description service for this node.") | |
| .set__read_only(true)); | |
| enabled = enable_param.get<bool>(); | |
| } catch (const rclcpp::exceptions::InvalidParameterTypeException & exc) { | |
| RCLCPP_ERROR(logger_, "%s", exc.what()); | |
| throw; | |
| } |
Notice how use_sim_time is declared instead:
rclcpp/rclcpp/src/rclcpp/time_source.cpp
Lines 254 to 274 in 7ebc9e4
| rclcpp::ParameterValue use_sim_time_param; | |
| const std::string use_sim_time_name = "use_sim_time"; | |
| if (!node_parameters_->has_parameter(use_sim_time_name)) { | |
| use_sim_time_param = node_parameters_->declare_parameter( | |
| use_sim_time_name, | |
| rclcpp::ParameterValue(false)); | |
| } else { | |
| use_sim_time_param = node_parameters_->get_parameter(use_sim_time_name).get_parameter_value(); | |
| } | |
| if (use_sim_time_param.get_type() == rclcpp::PARAMETER_BOOL) { | |
| if (use_sim_time_param.get<bool>()) { | |
| parameter_state_ = SET_TRUE; | |
| clocks_state_.enable_ros_time(); | |
| create_clock_sub(); | |
| } | |
| } else { | |
| RCLCPP_ERROR( | |
| logger_, "Invalid type '%s' for parameter 'use_sim_time', should be 'bool'", | |
| rclcpp::to_string(use_sim_time_param.get_type()).c_str()); | |
| throw std::invalid_argument("Invalid type for parameter 'use_sim_time', should be 'bool'"); | |
| } |
While use_sim_time is checked with has_parameter() call for existence, start_type_description_service declaration does not.
I believe this is a bug and should be fixed. If maintainers agree, I can open a PR.
BTW, I strongly believe that this kind of "standard node parameters" should share an almost identical way of declaring them, for code commonality.