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

Exception when declaring parameters after callback is set #769

Closed
Karsten1987 opened this issue Jun 24, 2019 · 12 comments
Closed

Exception when declaring parameters after callback is set #769

Karsten1987 opened this issue Jun 24, 2019 · 12 comments
Assignees
Labels
bug Something isn't working more-information-needed Further information is required

Comments

@Karsten1987
Copy link
Contributor

I am struggling with how to declare parameters for my diagnostic_updater. Specifically, I have the following setup: I am spawning the URG laser driver, which is a node and has a diagnostics updater instance as a class member variable. That diagnostics updater takes a node (or better node interfaces) in its constructor. The diagnostics updater has a parameter period which is meant to be updated dynamically. The URG node itself has multiple laser specific parameters declared as well.

Within code, this kind of looks like this:

Urg::Urg()
: rclcpp::Node("urg_laser_node")
{
  // Get parameters so we can change these later.
  this->declare_parameter<std::string>("ip_address", ip_address_);
  this->declare_parameter<int>("ip_port", ip_port_);
  this->declare_parameter<std::string>("laser_frame_id", laser_frame_id_);
  ...

  this->set_on_parameters_set_callback(std::bind(&UrgNode::param_change_callback, this, std::placeholders::_1));

  // the diagnostics_updater declares another parameter and results in an exception.
  diagnostic_updater_ = std::make_unique<diagnostic_updater::Updater>(
    this->get_node_base_interface(),
    this->get_node_topics_interface(),
    this->get_node_logging_interface(),
    this->get_node_parameters_interface());
  diagnostic_updater_->add("Hardware Status", this, &UrgNode::populateDiagnosticsStatus);
 
  // Having the parameter callback set at the very end, prevents the exception
  // this->set_on_parameters_set_callback(std::bind(&UrgNode::param_change_callback, this, std::placeholders::_1));
}

I am noticing two problems with this:

1.) When having set_on_parameters_set_callback called before initializing the diagnostics updater instance, I am unable to declare any parameter within the diagnostics instance as the assigned callback for the URG node is not aware of the diagnostics parameter and I get an exception:

libc++abi.dylib: terminating with uncaught exception of type rclcpp::exceptions::InvalidParameterValueException: parameter 'urg_node.diagnostics_updater_period' could not be set: The parameter urg_node.diagnostics_updater_period is not part of the reconfigurable parameters.

So I had to make sure that the parameter callback is set at last and no new parameters were declared after that.

2.) When modifying the URG callback in a way to catch a change of parameter for the diagnostics updater (i.e. the parameter "period"), I need public API on the diagnostics updater in order to set/get the current period on it. Plus, every other node which uses diagnostics, e.g. cartographer has to write the same logic in their code.

After thinking about this for a while, I'd like to have the parameter period being solely declared within the diagnostics updater and ideally have a callback for that parameter which is handled within the diagnostics updater itself.
I remember we talked about having multiple callbacks for parameters, especially with cases like use_sim_time. Is that possible with the current dashing API? If not, do you have any suggestions on how to handle that case?

@Karsten1987 Karsten1987 added the bug Something isn't working label Jun 24, 2019
@ivanpauno
Copy link
Member

  1. What is set_on_parameters_set_callback doing? Could you copy the code? It should be possible to register it before or after the parameters are declared.

  2. Multiple parameter callbacks are not possible now. I don't understand well why having multiple callbacks will solve the problem you are describing. Could you provide more context? Probably, the code of the callback will help.

@Karsten1987
Copy link
Contributor Author

The callback is rather long to be copied, but you can check the code here: https://github.com/ros-drivers/urg_node/pull/50/files#diff-d6a6026f1c3c9643497413ff2fc498caR271

It is basically checking for the parameters set in the URG node and returns false if not found. It does not have any notion of parameters needed for the diagnostics updater. This makes sense to me as I think the URG node should be able to use the diagnostic updater without knowing details about which parameters are set inside the diagnostic updater.

Why multiple callbacks are ideal? The diagnostic updater uses the node interfaces of the outer URG node. So it declares the diagnostics related parameters on the URG node parameter interface. If I could register multiple callbacks on the same parameter interface, then the URG node could use its callback to really only verify laser related parameters, whereas the diagnostic updater can use its own callback to only check for diagnostic related parameters and both don't interfere with each other.

The alternative right now is that every node which is using diagnostics has to know the intrinsics of it and deal with parameters and their changes respectively. That means, every time a new diagnostics parameter was to be introduced, every package using diagnostics has to be updated as well.

Does this make sense?

@ivanpauno
Copy link
Member

The callback is rather long to be copied, but you can check the code here: https://github.com/ros-drivers/urg_node/pull/50/files#diff-d6a6026f1c3c9643497413ff2fc498caR271

The callback looks good. I will try to do a simpler repro, as it should be possible to register the callback before declaring the parameters.

Why multiple callbacks are ideal? The diagnostic updater uses the node interfaces of the outer URG node. So it declares the diagnostics related parameters on the URG node parameter interface. If I could register multiple callbacks on the same parameter interface, then the URG node could use its callback to really only verify laser related parameters, whereas the diagnostic updater can use its own callback to only check for diagnostic related parameters and both don't interfere with each other.

The alternative right now is that every node which is using diagnostics has to know the intrinsics of it and deal with parameters and their changes respectively. That means, every time a new diagnostics parameter was to be introduced, every package using diagnostics has to be updated as well.

Does this make sense?

Ok, now I understand better. I think that adding the ability of registering multiple callbacks would be good.
As a fast workaround, I can add a getter get_on_parameters_set_callback. So you can first get the current callback, and wrap it with the new one.
The only tricky thing, is that you have to first do set_on_parameters_set_callback, and then initialize the diagnostics_updater (which will do the get, wrap, set trick).

Well, maybe it's better just to add multiple callbacks ....

@ivanpauno
Copy link
Member

ivanpauno commented Jun 25, 2019

@Karsten1987 About the bug (calling set_on_parameters_set_callback before declaring the parameters), I haven't been able to reproduce it in a simpler example. Reading the rclcpp code, that shouldn't be a problem.
Could you dig a little bit more into it? If not, give me details about how to reproduce it in your use case, and I will try to find where the bug is.

Edit:
A traceback of the exception would be a good starting point.

@ivanpauno
Copy link
Member

@Karsten1987 #772 added support to multiple on parameters set callbacks.

@Karsten1987
Copy link
Contributor Author

Great work @ivanpauno. I haven't gotten around to test it, but from what I've seen I think it's on the spot. I'll give it a shot ASAP.

@Karsten1987
Copy link
Contributor Author

@ivanpauno I finally had some time to continue working on this. It looks to me as if I am still doing something wrong.

I've uploaded a little dummy project here to illustrate what I am trying to do:
https://github.com/karsten1987/parameter_test

To give a little bit context to that package:

There are two sorts of node packages sketched.

  • An OuterNode class which indeed inherits from rclcpp::Node and therefore is a node.
  • An InnerNode class which takes the OuterNode as a argument in the constructor.

Keep in mind that both classes in this case could be potentially be written by two individually packages (i.e. URG and Diagnostics), where the InnerNode potentially doesn't know anything about the OuterNode calling it.

If you build and run this package, you'll get the following error:

 ➭ ros2 run parameter_test main
hello world parameter_test package
setting a new set of outer_node parameters
libc++abi.dylib: terminating with uncaught exception of type rclcpp::exceptions::InvalidParameterValueException: parameter 'my_double_parameter' could not be set:

Which indicates that in this case only the callback set in the outer node class is taken into consideration:
https://github.com/Karsten1987/parameter_test/blob/66b3fc9c15c0a457de6d63ccd9f3fd8a333c9ec0/include/parameter_test/outer_node.hpp#L27

When I then go ahead and change the order here, meaning adding the callback after declaring the inner node parameter, I get the following order:

 ➭ ros2 run parameter_test main
hello world parameter_test package
setting a new set of inner_node parameters
correct double parameter found
setting a new set of outer_node parameters
libc++abi.dylib: terminating with uncaught exception of type rclcpp::exceptions::InvalidParameterValueException: parameter 'my_double_parameter' could not be set:

Which means, it's taking the correct callback (it parses its parameter correctly), but fails after. I am a bit puzzled about it, but I feel that the call fails because the second callback of the outer node fails. That does mean the order of the callbacks matter? Could this assumption be correct or am I doing something wrong? I am a bit puzzled here.


In general, two more questions came into my mind while testing:

1.) Given that the two nodes might be developed independently (as I motivated with the URG and Diagnostics) should the set_on_parameters_set_callback function be deprecated as this basically forbids to declare parameters after that?
2.) Is it recommended to always set the callback functions before declaring the parameter?

@ivanpauno
Copy link
Member

@ivanpauno I finally had some time to continue working on this. It looks to me as if I am still doing something wrong.

The problem is that your callbacks are by default rejecting a change, when they should be accepting it. Callback results are combined like an AND gate, and not like an OR gate. Change in this two lines false->true, and the code will work.

https://github.com/Karsten1987/parameter_test/blob/66b3fc9c15c0a457de6d63ccd9f3fd8a333c9ec0/include/parameter_test/outer_node.hpp#L38
https://github.com/Karsten1987/parameter_test/blob/66b3fc9c15c0a457de6d63ccd9f3fd8a333c9ec0/include/parameter_test/inner_node.hpp#L29


1.) Given that the two nodes might be developed independently (as I motivated with the URG and Diagnostics) should the set_on_parameters_set_callback function be deprecated as this basically forbids to declare parameters after that?

I agree that set_on_parameters_set_callback callback should be deprecated (issue here), as it has no sense to provide two APIs for setting callbacks.
But AFAIK, set_on_parameters_set_callback doesn't forbid declaring a parameter after being called
If it does, it's a bug that should be solved and backported to Dashing (I tried to reproduce the issue and I couldn't).

2.) Is it recommended to always set the callback functions before declaring the parameter?

Yes, that will validate the default value of the parameter or the override provided by the user (override=value provided as command line argument).

@Karsten1987
Copy link
Contributor Author

I somehow feel that defaulting to true as a return value is ambiguous. That would mean to me that if the parameter is not found my call to set parameter is still being executed correctly and one doesn't know from the caller side whether the parameter was actually set or not.
Whereas, if we connected the callbacks via a logical OR, that ambiguity would go away in my opinion.
What do you think?

But AFAIK, set_on_parameters_set_callback doesn't forbid declaring a parameter after being called

It somehow does if the previously set callback doesn't default to true.

@ivanpauno
Copy link
Member

I somehow feel that defaulting to true as a return value is ambiguous. That would mean to me that if the parameter is not found my call to set parameter is still being executed correctly and one doesn't know from the caller side whether the parameter was actually set or not.
Whereas, if we connected the callbacks via a logical OR, that ambiguity would go away in my opinion.
What do you think?

The idea is to have both on_parameter_set and on_parameter_updated callbacks. The first is used only to accept/reject parameters, the later already knows which parameters have been set.
Currently, the only way to have a on_parameter_updated callback is to subscribe to the parameter events topic, we should add a local alternative to that (see #609).
If all the callbacks are checking a disjoint set of parameters, combining them with a logical OR is fine, and it avoids the need of a parameter event callback. But, it's less flexible than combining them with a logical AND (and having both types of callbacks).

@Karsten1987
Copy link
Contributor Author

If all the callbacks are checking a disjoint set of parameters, combining them with a logical OR is fine, and it avoids the need of a parameter event callback. But, it's less flexible than combining them with a logical AND (and having both types of callbacks).

Can you give an example of how two callbacks attached to the same node are not checking a disjoint set of parameters?


I am going to close this issue as I believe the actual topic of this issue - the exception - is being addressed. I am not convinced that the logical AND is the best solution here, but that's out of scope for this issue.

@ivanpauno
Copy link
Member

Can you give an example of how two callbacks attached to the same node are not checking a disjoint set of parameters?

It's not an usual case, but I prefer not limiting the implementation to it.
Maybe, you want to temporary reject any parameter update. In that case you can add a callback rejecting the updates and later remove it.

I think that it's a good idea to bring up the discussion in a team meeting, and decide if we want to go with on_parameter_set and on_parameter_updated callback style, or just having on_parameter_set and combining them with a logical OR.

nnmm pushed a commit to ApexAI/rclcpp that referenced this issue Jul 9, 2022
* Add coverage tests wait module
* Add fault injection test
* Add zero_init allocator test to init
* Remove bomb allocator test
* Add better handling fault injection
* Add comment to fault injection tests
* Move test to another section

Signed-off-by: Jorge Perez <jjperez@ekumenlabs.com>
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
bug Something isn't working more-information-needed Further information is required
Projects
None yet
Development

No branches or pull requests

2 participants