Skip to content

Commit

Permalink
Need to specify NodeOption explicitly to allow declaration. (#389)
Browse files Browse the repository at this point in the history
* specify NodeOption explicitly to allow declaration.

Signed-off-by: Tomoya.Fujita <Tomoya.Fujita@sony.com>

* replace deprecated API for parameter event into new API.

Signed-off-by: Tomoya.Fujita <Tomoya.Fujita@sony.com>

* fix issue rclcpp#851.

Signed-off-by: Tomoya.Fujita <Tomoya.Fujita@sony.com>
  • Loading branch information
fujitatomoya authored and ivanpauno committed Oct 2, 2019
1 parent d8afaec commit f3d61e6
Show file tree
Hide file tree
Showing 2 changed files with 13 additions and 19 deletions.
20 changes: 7 additions & 13 deletions demo_nodes_cpp/src/parameters/even_parameters_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,27 +26,18 @@ class EvenParameterNode : public rclcpp::Node
{
public:
DEMO_NODES_CPP_PUBLIC
explicit EvenParameterNode(const rclcpp::NodeOptions options)
: Node("even_parameters_node", options)
explicit EvenParameterNode(rclcpp::NodeOptions options)
: Node("even_parameters_node", options.allow_undeclared_parameters(true))
{
// Force flush of the stdout buffer.
setvbuf(stdout, NULL, _IONBF, BUFSIZ);
// Declare a parameter change request callback
// This function will enforce that only setting even integer parameters is allowed
// any other change will be discarded
auto existing_callback = this->set_on_parameters_set_callback(nullptr);
auto param_change_callback =
[this, existing_callback](std::vector<rclcpp::Parameter> parameters)
[this](std::vector<rclcpp::Parameter> parameters)
{
auto result = rcl_interfaces::msg::SetParametersResult();
// first call the existing callback, if there was one
if (nullptr != existing_callback) {
result = existing_callback(parameters);
// if the existing callback failed, go ahead and return the result
if (!result.successful) {
return result;
}
}
result.successful = true;
for (auto parameter : parameters) {
rclcpp::ParameterType parameter_type = parameter.get_type();
Expand Down Expand Up @@ -84,8 +75,11 @@ class EvenParameterNode : public rclcpp::Node
}
return result;
};
this->set_on_parameters_set_callback(param_change_callback);
// callback_handler needs to be alive to keep the callback functional
callback_handler = this->add_on_set_parameters_callback(param_change_callback);
}

OnSetParametersCallbackHandle::SharedPtr callback_handler;
};

} // namespace demo_nodes_cpp
Expand Down
12 changes: 6 additions & 6 deletions demo_nodes_cpp/src/parameters/parameter_blackboard.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,12 +29,12 @@ class ParameterBlackboard : public rclcpp::Node
public:
DEMO_NODES_CPP_PUBLIC
explicit ParameterBlackboard(
const rclcpp::NodeOptions & options = (
rclcpp::NodeOptions()
.allow_undeclared_parameters(true)
.automatically_declare_parameters_from_overrides(true)
))
: Node("parameter_blackboard", options)
rclcpp::NodeOptions options
)
: Node(
"parameter_blackboard",
options.allow_undeclared_parameters(true).
automatically_declare_parameters_from_overrides(true))
{
RCLCPP_INFO(this->get_logger(),
"Parameter blackboard node named '%s' ready, and serving '%zu' parameters already!",
Expand Down

0 comments on commit f3d61e6

Please sign in to comment.