ros2 / rclcpp

rclcpp (ROS Client Library for C++)
Apache License 2.0
517 stars 412 forks source link

Should the `automatically_declare_parameters_from_overrides` node option be deprecated and removed? #2189

Open schornakj opened 1 year ago

schornakj commented 1 year ago

As far as I understand, the automatically_declare_parameters_from_overrides node option was added during the Crystal->Dashing transition to allow users to keep using code written for Crystal without being forced to immediately migrate to the parameter declaration and description system added in Dashing.

I think that the intent back then was to eventually migrate all use of parameters to the declarative approach. I found some discussions like the one in #730 that refer to automatic declaration as something that should be avoided in all but a few niche situations. However, since the automatically_declare_parameters_from_overrides option has remained available in all releases since then, it's still possible to write code that uses it -- it's even tempting to do so, because the parameter declaration and description API is quite verbose and relying on automatic declaration requires less developer legwork.

This has left parameters in rclcpp in a messy situation because code written with the expectation that automatically_declare_parameters_from_overrides is enabled is not functionally compatible with code written for explicit parameter declaration:

An example of a troublesome situation is if someone creates a class that gets parameters but does not declare them. If I want to include that class as a member of my own node class, then I am required to set automatically_declare_parameters_from_overrides to true in order to make that class work correctly, which then limits how I can use parameters within my own code.

Summarizing my questions for discussion:

fujitatomoya commented 1 year ago

@schornakj thanks for bring this up. since that comes from discussion in history, i personally am not sure what would be the right path to take. personally, especially production stage, i would avoid using automatically_declare_parameters_from_overrides as enabled.

fujitatomoya commented 1 year ago

CC: @ros2/team

clalancette commented 1 year ago

Looking at this, I think we need to leave this option in place. For instance, without automatically_declare_parameters_from_overrides, it would not be possible to create a blackboard node in ROS 2. And further, looking through all of the packages released into Rolling, I count at least a dozen that currently use it for one reason or another.

That said, I can definitely see that we could clean some of these situations up and make them more consistent.

If automatically_declare_parameters_from_overrides == false, then getting the value of an undeclared parameter using get_parameter_or will always return the fallback value, even if YAML text containing a map of parameters has been passed to the node from the command line or in a launch file.

This one in particular seems like a bug, or at least odd behavior that should be clarified.

schornakj commented 1 year ago

For instance, without automatically_declare_parameters_from_overrides, it would not be possible to create a blackboard node in ROS 2.

Do you have an example of a package with a node that implements this pattern? The idea of a blackboard node or shared parameter server is also mentioned in previous discussion about parameter overrides, so it was clearly important to the people who designed the node parameter interface, but I've never actually encountered it in the wild.

And further, looking through all of the packages released into Rolling, I count at least a dozen that currently use it for one reason or another.

I can't speak for other packages, but MoveIt2 and ros2_control are reworking how they declare and retrieve parameters (see this discussion, for example). As a result from this, these packages will no longer need to use automatically_declare_parameters_from_overrides because all parameters required by planner plugins, etc., will be consistently declared. I'd bet that other projects that currently use this node option are in similar situations, and that making sure all required parameters are declared would remove the need for the automatic declaration as well.

clalancette commented 1 year ago

Do you have an example of a package with a node that implements this pattern? The idea of a blackboard node or shared parameter server is also mentioned in previous discussion about parameter overrides, so it was clearly important to the people who designed the node parameter interface, but I've never actually encountered it in the wild.

https://github.com/ros2/demos/blob/019b64d5ed5d5540212dab275121dc76ccef18cb/demo_nodes_cpp/src/parameters/parameter_blackboard.cpp is the canonical example. I don't know how heavily it is used, though.

saikishor commented 8 months ago

I can't speak for other packages, but MoveIt2 and ros2_control are reworking how they declare and retrieve parameters (see this discussion, for example). As a result from this, these packages will no longer need to use automatically_declare_parameters_from_overrides because all parameters required by planner plugins, etc., will be consistently declared. I'd bet that other projects that currently use this node option are in similar situations, and that making sure all required parameters are declared would remove the need for the automatic declaration as well.

For ros2_control, there is a problem that we cannot define the dynamic parameter maps without knowing the initial list. This is creating a huge problem to be declare the block of parameters that are based on the initial list

For example, the following case

joints: ["joint_1", "joint_2"]
joint_1:
  type: rotary
  frame: joint_1_link
joint_2:
  type: rotary
  frame: joint_2_link

To parse such a block, we need to know the joint_names at the time of declaration, and this is currently not possible. If there is a way to declare the parameters without having to set the nodeOption automatically_declare_parameters_from_overrides would be helpful.

std::vector<JointParams> joint_params;
auto joint_names = node->declare_parameter<std::vector<std::string>>("joints", std::vector<std::string>());
for (auto joint : joint_names)
{
  RCLCPP_INFO(logger, "Adding Joint: %s", joint.c_str());
  JointParams params;
  params.name = name;
  params.type = node->declare_parameter<std::string>(name + ".type", std::string());
  params.frame = node->declare_parameter<std::string>(name + ".frame", std::string());
  params.param_name = node->declare_parameter<std::string>(name + ".param_name", std::string());
  joint_params.push_back(params);
}
schornakj commented 8 months ago

@saikishor one approach I've used to do that sort of thing is conditionally declaring parameters very close to their point of use. I haven't tested this in a situation that's identical to the one in ros2_control, but I think this should work:

if (!node->has_parameter("joints")
{
  node->declare_parameter<std::vector<std::string>>("joints", std::vector<std::string>());
}
auto joint_names = node->get_parameter<std::vector<std::string>>("joints");
for (const auto& joint_name : joint_names)
{
  if (!node->has_parameter(joint_name + ".type")
  {
    ...
  }
    ...
}

While this certainly has more complex code than the existing automatically_declare_parameters_from_overrides == true case, the actions of declaring a parameter vs. retrieving a parameter are at least explicitly written out in the code with clear conditions rather than being handled invisibly behind the scenes.

e: The reason for the separate declare_parameter and get_parameter calls are that declaring a parameter that has already been declared throws an exception.

schornakj commented 8 months ago

https://github.com/ros2/demos/blob/019b64d5ed5d5540212dab275121dc76ccef18cb/demo_nodes_cpp/src/parameters/parameter_blackboard.cpp is the canonical example. I don't know how heavily it is used, though.

@clalancette one way to measure how many projects use this pattern is to search Github for uses of rcl_interfaces::srv::ListParameters, which shows some projects that have copied and extended the demo you linked. There are a handful of them out there (plus many forks of rclcpp).

I think where I'm at on this is that while this pattern might be useful to some people and projects, there are ways to get there that do not depend on ROS 2 parameters and specific implementation details of ROS 2 nodes. Simplifying the mechanism for declaring and retrieving parameters would create a greater benefit across more projects than would be lost by removing this specific way of creating a parameter blackboard server.

clalancette commented 8 months ago

I think where I'm at on this is that while this pattern might be useful to some people and projects, there are ways to get there that do not depend on ROS 2 parameters and specific implementation details of ROS 2 nodes.

Can you expand on this more? In particular, how would you implement a global blackboard node?

saikishor commented 8 months ago

Thank you @schornakj for your insight.

While this certainly has more complex code than the existing automatically_declare_parameters_from_overrides == true case, the actions of declaring a parameter vs. retrieving a parameter are at least explicitly written out in the code with clear conditions rather than being handled invisibly behind the scenes.

e: The reason for the separate declare_parameter and get_parameter calls are that declaring a parameter that has already been declared throws an exception.

I agree with you that for most of the cases, we have to declare the parameters should be explicitly declared. However, this won't be the case for usual use cases, for instance, I have a map of predefined motions and the users can create motions to use later, but this map of motions cannot be known earlier as the end user might give a different name.

/play_motion2:
  ros__parameters:

    # params for first position approach
    approach_velocity: 0.5        # default 0.5
    approach_min_duration: 0.0    # default 0.0

    motions_list: ["motion_1", "motion_2", "motion_3"...]
    motions:
      motion_1:
        joints: [joint1, joint2]
        positions: [0.0, 0.0,
                    0.5, 0.25]
        times_from_start: [0.5, 1.0]
        meta:
          name: Motion_1
          usage: example
          description: 'Example Motion'

      motion_2:
        ...

      motion_3:
        ...

For the case presented above, I know the elements inside this mapping joints, positions, time_from_start and the meta info before, but the only thing, I will know at the execution time are the keys to this map, so, in order to achieve it, there should be a way to be able to declare them. I've also opened an issue: https://github.com/ros2/rclcpp/issues/2367 in order to discuss if this is possible. I'm discussing here to see if this has already been addressed.

@clalancette @schornakj how can such a case be handled without setting the NodeOptions to allow_undeclared_parameters and automatically_declare_parameters_from_overrides.

Thank you,

lynassif commented 4 months ago

I also have a situation where certain parameters are dynamically declared when a certain plugin is executed. However, I need these parameters to be available at application startup. automatically_declare_parameters_from_overrides has helped me achieve the desired behavior.

tfoote commented 4 months ago

I would suggest that in the case flagged in the original

An example of a troublesome situation is if someone creates a class that gets parameters but does not declare them.

In most cases ticket that as a bug/enhancement request.

We have several use cases demonstrated for which this is valuable. Since this is an override from the default people are using it specifically to solve a purpose. I'd suggest that we not deprecate and remove this unless we come up with a fully covering alternative approach.