Skip to content
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

Set parameters from inside callbacks #1789

Closed
wants to merge 2 commits into from

Conversation

adityapande-1995
Copy link
Contributor

@adityapande-1995 adityapande-1995 commented Sep 28, 2021

This PR aims to add a way to set parameters from inside another parameter's callback.

Current approach :

  • Maintain a separate vector container for callbacks passed using the allowRecursion boolean flag to add_on_set_parameters method.
  • Maintain a loop counter and a context tracker to allow only recursive container callbacks to be called when set_parameters_atomically is called from inside another parameter's callback.

TODO for current approach :

  • Manage loop counter and recursive access to add_on_set_parameters, remove_on_set_parameters, undeclare_parameters
  • Clean up code, remove debug prints

Concerns

  • Complicated locking and overall approach
  • Thread safety
  • Order in which callbacks are run can be difficult to understand for the user, which may lead to unexpected behavior of parameter actions

Suggested alternatives

  • Have a new action called update_parameters which would update the parameters without triggering their callbacks. This would not solve the overall problem exactly, but would be much simpler to debug and understand.
  • Maybe have this action inside get_parameters ?

Original model :

image

Current approach :

image

Signed-off-by: Aditya Pande <aditya050995@gmail.com>
Signed-off-by: Aditya Pande <aditya050995@gmail.com>
@adityapande-1995 adityapande-1995 marked this pull request as draft September 28, 2021 19:38
@adityapande-1995
Copy link
Contributor Author

adityapande-1995 commented Sep 28, 2021

Example usage :

#include "rclcpp/rclcpp.hpp"
#include <iostream>
class MyNode : public rclcpp::Node
{
public:
    MyNode() : Node("my_node_name")
    {
        auto param_change_callback_1 =
        [this](std::vector<rclcpp::Parameter> parameters) {
          auto result = rcl_interfaces::msg::SetParametersResult();
          result.successful = true;

          for (const auto & parameter : parameters) {
            std::string param_name = parameter.get_name();
            std::cout << "cb1 -- dwnstream cb param name:" << param_name <<std::endl;
            // This would lead to a runtime exception
            // if (param_name == "my_int2") {
            //   std::cout << "dwnstream: Trying to set my_int1" << std::endl;
            //   this->set_parameter(rclcpp::Parameter("my_int1", 5));
            // }

        }
        return result;
      };
        
        auto param_change_callback_2 =
        [this](std::vector<rclcpp::Parameter> parameters) {
          auto result = rcl_interfaces::msg::SetParametersResult();
          result.successful = true;

          for (const auto & parameter : parameters) {
            std::string param_name = parameter.get_name();
            std::cout << "cb2 -- dwnstream cb param name:" << param_name <<std::endl;
            // This works !
            if (param_name == "my_int2") {
              std::cout << "dwnstream: Trying to set my_int1" << std::endl;
              this->set_parameter(rclcpp::Parameter("my_int1", 10));
            }
        }
        return result;
      };

      this->callback_handle_1 = this->add_on_set_parameters_callback(param_change_callback_1);
      this->callback_handle_2 = this->add_on_set_parameters_callback(param_change_callback_2, true);

      this->declare_parameter("my_int1", 0);
      this->declare_parameter("my_int2", 0);
    }
private:
    rclcpp::Node::OnSetParametersCallbackHandle::SharedPtr callback_handle_1;
    rclcpp::Node::OnSetParametersCallbackHandle::SharedPtr callback_handle_2;
};


int main(int argc, char **argv)
{
    rclcpp::init(argc, argv);
    auto node = std::make_shared<MyNode>();
    rclcpp::spin(node);
    rclcpp::shutdown();
    return 0;
}

Copy link
Member

@ivanpauno ivanpauno left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Could you explain what is the current behavior when calling set_parameter() from a parameter callback and how does this PR solve the issue?

I took a quick look and the approach taken here seems to be fairly complicated.

@@ -929,7 +929,7 @@ class Node : public std::enable_shared_from_this<Node>
RCLCPP_PUBLIC
RCUTILS_WARN_UNUSED
OnSetParametersCallbackHandle::SharedPtr
add_on_set_parameters_callback(OnParametersSetCallbackType callback);
add_on_set_parameters_callback(OnParametersSetCallbackType callback, bool allowRecursion = false);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I don't like the idea of having an allowRecursion, we should either always support recursion or not at all.
nit

Suggested change
add_on_set_parameters_callback(OnParametersSetCallbackType callback, bool allowRecursion = false);
add_on_set_parameters_callback(OnParametersSetCallbackType callback, bool allow_recursion = false);

@ivanpauno
Copy link
Member

Could you explain what is the current behavior when calling set_parameter() from a parameter callback and how does this PR solve the issue?

Is the current issue iterator invalidation here?

while (it != callback_container.end()) {
auto shared_handle = it->lock();
if (nullptr != shared_handle) {
result = shared_handle->callback(parameters);
if (!result.successful) {
return result;
}
it++;
} else {
it = callback_container.erase(it);
}

@adityapande-1995
Copy link
Contributor Author

adityapande-1995 commented Sep 29, 2021

@ivanpauno curently, if you call set_parameter() from inside a callback, the ParameterMutationRecursionGuard does not allow this, and throws a runtime exception saying that this operation is not allowed from inside a callback. Exact line :

ParameterMutationRecursionGuard guard(parameter_modification_enabled_);

As discussed with @wjwwood and @clalancette , we want to enable this functionality, to make sort of "meta-parameters" that can trigger other parameter actions. Of course this can lead to an infinite recursion (where parameters can call each other in a circular manner) and users can mess up things easily. Thus we wanted an explicit flag, or a new callback group container that would hold such callbacks which can be used from inside other callbacks. I've also added a loop_counter to keep track of the recursion depth and exit if we exceed it.

We could consider removing the ParameterMutationRecursionGuard entirely, but the users would have no way of explicitly knowing that they are risking infinite recursion.

@ivanpauno
Copy link
Member

The "on set parameter" callbacks doesn't seem to be a good for this though.
IIUC they are supposed to only be checking if the parameter is going to be accepted or rejected, and not to have side-effects.
The issue with having side-effects in the callback is that the parameter might end up not being set, because another callback rejected it.

As discussed with @wjwwood and @clalancette , we want to enable this functionality, to make sort of "meta-parameters" that can trigger other parameter actions

Could you give an example of where this is needed? That might help me to understand the issue in a better way.

@adityapande-1995
Copy link
Contributor Author

adityapande-1995 commented Sep 29, 2021

After a discussion with @jacobperron @clalancette @mjeronimo @ivanpauno and looking at #1190, #609, it was decided that ros-simulation/gazebo_ros_pkgs#1312 would use Parameter Event handler to reflect the true values of the slip parameters, and the ideal solution in rclcpp would be to have a self callback in the node, which would trigger when a parameter is changed. This should not be a validation callback.

Another major issue with this PR was that the callbacks are meant to be validation callbacks, and setting parameters inside them is not the intended use case. If one of the set_parameter action in the entire chain fails, then first callback that started the entire chain would fail as well. Other solutions about just updating the parameter value and not trigger its callbacks were also discussed, but these were not solving the actual problem at hand.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

2 participants