rclcpp
rclcpp copied to clipboard
inconsistent declare/undeclare parameter behaviour
current behaviour
A ROS node can:
- explicitly declare a parameter via
declare_parameterand explicitly undeclare it viaundeclare_parameter - implicitly declare a parameter by setting the option
allow_undeclared_parameters(true)and then just setting the parameter viaset_parameterand implicitly undeclare a dynamic parameter by changing its type toPARAMETER_NOT_SET
It is also possible to mix these modes and implicitly undeclare an explicitly declared parameter by not allowing undeclared parameters, using dynamic parameter types and then setting its type to PARAMETER_NOT_SET. In such a situation, it will not be possible to "reactivate" the parameter again, without the node explicitly declaring the parameter again.
This mix of explicit creating and implicit deletion of parameters is inconsistent.
expected behaviour
If an explicitly declared dynamic parameters type is changed to PARAMETER_NOT_SET, it should result into the same behaviour as declaring the parameter with PARAMETER_NOT_SET in the first place. That means, after changing the type to PARAMETER_NOT_SET, has_parameter must return true and ros2 param get should return Parameter not set. and ros2 param dump should show the value as null.
Additionally, it would be useful if this would still work with static types, such that a parameter has a static type and its value is either be set or unset (null), comparable to a NULL pointer in C.
The current implicitly undeclare behaviour should only apply when allow_undeclared_parameters is true and parameters are declared implicitly via set_parameter.
If an explicitly declared dynamic parameters type is changed to PARAMETER_NOT_SET, it should result into the same behaviour as declaring the parameter with PARAMETER_NOT_SET in the first place. That means, after changing the type to PARAMETER_NOT_SET, has_parameter must return true and ros2 param get should return Parameter not set. and ros2 param dump should show the value as null.
this sounds correct to me.
could you provide the short, self contained example code snippet here what SHOULT NOT be done? i think that would be useful.
this sounds correct to me.
could you provide the short, self contained example code snippet here what SHOULT NOT be done? i think that would be useful.
Run the node (full project: param_example.zip):
#include <memory>
#include <rclcpp/rclcpp.hpp>
#include <std_srvs/srv/empty.hpp>
class ParamNode : public rclcpp::Node
{
public:
ParamNode() : Node("param_test")
{
rcl_interfaces::msg::ParameterDescriptor descriptor;
descriptor.dynamic_typing = true;
const rclcpp::ParameterValue & a =
this->declare_parameter("a", rclcpp::ParameterValue{}, descriptor, true);
srv = this->create_service<std_srvs::srv::Empty>(
"parameter_test", [this, &a](
const std_srvs::srv::Empty::Request::SharedPtr & /*request*/,
const std_srvs::srv::Empty::Response::SharedPtr & /*response*/) {
// default uninitialised
const rclcpp::Parameter a1 = this->get_parameter("a");
RCLCPP_INFO_STREAM(
this->get_logger(), "has 'a': " << this->has_parameter("a") << ", type: '" << a.get_type()
<< "', value: '" << rclcpp::to_string(a) << "'");
// set to PARAMETER_STRING
this->set_parameter({"a", rclcpp::ParameterValue{"test"}});
RCLCPP_INFO_STREAM(
this->get_logger(), "has 'a': " << this->has_parameter("a") << ", type: '" << a.get_type()
<< "', value: '" << rclcpp::to_string(a) << "'");
// set parameter to PARAMETER_NOT_SET
this->set_parameter({"a", rclcpp::ParameterValue{}});
RCLCPP_INFO_STREAM(
this->get_logger(), "has 'a': " << this->has_parameter("a") << ", type: '" << a.get_type()
<< "', value: '" << rclcpp::to_string(a) << "'");
});
}
private:
rclcpp::Service<std_srvs::srv::Empty>::SharedPtr srv;
};
int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<ParamNode>());
rclcpp::shutdown();
return 0;
}
and call its service (ros2 service call /parameter_test std_srvs/srv/Empty "{}").
You will see that the initial parameter is PARAMETER_NOT_SET and defined, but is, as per API documentation, implicitly undeclared once you switch to a type and back:
[param_test]: has 'a': 1, type: 'not set', value: 'not set'
[param_test]: has 'a': 1, type: 'string', value: 'test'
[param_test]: has 'a': 0, type: 'not set', value: 'not set'
Since the parameter a was declared explicitly without type and value via a default constructed rclcpp::ParameterValue (output line 1), setting it back to a default constructed rclcpp::ParameterValue should keep it declared and has_parameter should return true instead of false (output line 3).
Or in other words, setting a parameter via:
declare_parameter("a", rclcpp::ParameterValue{}, [...]);
should have the same effect as:
set_parameter({"a", rclcpp::ParameterValue{}});
as observed by the public ROS API.
@christianrauch thanks, i will look into it.
I believe @fujitatomoya already has a PR for this.