diff --git a/demo_nodes_cpp/src/parameters/even_parameters_node.cpp b/demo_nodes_cpp/src/parameters/even_parameters_node.cpp index fab5bc157..3d64deb7a 100644 --- a/demo_nodes_cpp/src/parameters/even_parameters_node.cpp +++ b/demo_nodes_cpp/src/parameters/even_parameters_node.cpp @@ -26,10 +26,19 @@ class EvenParameterNode : public rclcpp::Node // 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](std::vector parameters) -> rcl_interfaces::msg::SetParametersResult + [this, existing_callback](std::vector 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(); @@ -67,7 +76,7 @@ class EvenParameterNode : public rclcpp::Node } return result; }; - this->register_param_change_callback(param_change_callback); + this->set_on_parameters_set_callback(param_change_callback); } }; diff --git a/demo_nodes_cpp/src/parameters/list_parameters.cpp b/demo_nodes_cpp/src/parameters/list_parameters.cpp index 07a703250..9aba49bb6 100644 --- a/demo_nodes_cpp/src/parameters/list_parameters.cpp +++ b/demo_nodes_cpp/src/parameters/list_parameters.cpp @@ -28,6 +28,14 @@ int main(int argc, char ** argv) auto node = rclcpp::Node::make_shared("list_parameters"); + // Declare parameters that may be set on this node + node->declare_parameter("foo"); + node->declare_parameter("bar"); + node->declare_parameter("baz"); + node->declare_parameter("foo.first"); + node->declare_parameter("foo.second"); + node->declare_parameter("foobar"); + auto parameters_client = std::make_shared(node); while (!parameters_client->wait_for_service(1s)) { if (!rclcpp::ok()) { diff --git a/demo_nodes_cpp/src/parameters/list_parameters_async.cpp b/demo_nodes_cpp/src/parameters/list_parameters_async.cpp index c6c6721f1..d6430bdbc 100644 --- a/demo_nodes_cpp/src/parameters/list_parameters_async.cpp +++ b/demo_nodes_cpp/src/parameters/list_parameters_async.cpp @@ -28,7 +28,16 @@ int main(int argc, char ** argv) auto node = rclcpp::Node::make_shared("list_parameters_async"); + // Declare parameters that may be set on this node + node->declare_parameter("foo"); + node->declare_parameter("bar"); + node->declare_parameter("baz"); + node->declare_parameter("foo.first"); + node->declare_parameter("foo.second"); + node->declare_parameter("foobar"); + auto parameters_client = std::make_shared(node); + while (!parameters_client->wait_for_service(1s)) { if (!rclcpp::ok()) { RCLCPP_ERROR(node->get_logger(), "Interrupted while waiting for the service. Exiting."); diff --git a/demo_nodes_cpp/src/parameters/parameter_events.cpp b/demo_nodes_cpp/src/parameters/parameter_events.cpp index 500d10587..971705c20 100644 --- a/demo_nodes_cpp/src/parameters/parameter_events.cpp +++ b/demo_nodes_cpp/src/parameters/parameter_events.cpp @@ -50,6 +50,12 @@ int main(int argc, char ** argv) auto node = rclcpp::Node::make_shared("parameter_events"); + // Declare parameters that may be set on this node + node->declare_parameter("foo"); + node->declare_parameter("bar"); + node->declare_parameter("baz"); + node->declare_parameter("foobar"); + auto parameters_client = std::make_shared(node); while (!parameters_client->wait_for_service(1s)) { if (!rclcpp::ok()) { diff --git a/demo_nodes_cpp/src/parameters/parameter_events_async.cpp b/demo_nodes_cpp/src/parameters/parameter_events_async.cpp index e22e9d10f..f7982dafa 100644 --- a/demo_nodes_cpp/src/parameters/parameter_events_async.cpp +++ b/demo_nodes_cpp/src/parameters/parameter_events_async.cpp @@ -29,6 +29,12 @@ class ParameterEventsAsyncNode : public rclcpp::Node ParameterEventsAsyncNode() : Node("parameter_events") { + // Declare parameters that may be set on this node + this->declare_parameter("foo"); + this->declare_parameter("bar"); + this->declare_parameter("baz"); + this->declare_parameter("foobar"); + // Typically a parameter client is created for a remote node by passing the name of the remote // node in the constructor; in this example we create a parameter client for this node itself. parameters_client_ = std::make_shared(this); diff --git a/demo_nodes_cpp/src/parameters/set_and_get_parameters.cpp b/demo_nodes_cpp/src/parameters/set_and_get_parameters.cpp index 19d283834..5d24bde22 100644 --- a/demo_nodes_cpp/src/parameters/set_and_get_parameters.cpp +++ b/demo_nodes_cpp/src/parameters/set_and_get_parameters.cpp @@ -29,6 +29,14 @@ int main(int argc, char ** argv) auto node = rclcpp::Node::make_shared("set_and_get_parameters"); + // Declare parameters that may be set on this node + node->declare_parameter("foo"); + node->declare_parameter("bar"); + node->declare_parameter("baz"); + node->declare_parameter("foobar"); + node->declare_parameter("foobarbaz"); + node->declare_parameter("toto"); + auto parameters_client = std::make_shared(node); while (!parameters_client->wait_for_service(1s)) { if (!rclcpp::ok()) { diff --git a/demo_nodes_cpp/src/parameters/set_and_get_parameters_async.cpp b/demo_nodes_cpp/src/parameters/set_and_get_parameters_async.cpp index ff9adc7ff..7daa5973d 100644 --- a/demo_nodes_cpp/src/parameters/set_and_get_parameters_async.cpp +++ b/demo_nodes_cpp/src/parameters/set_and_get_parameters_async.cpp @@ -29,6 +29,14 @@ int main(int argc, char ** argv) auto node = rclcpp::Node::make_shared("set_and_get_parameters_async"); + // Declare parameters that may be set on this node + node->declare_parameter("foo"); + node->declare_parameter("bar"); + node->declare_parameter("baz"); + node->declare_parameter("foobar"); + node->declare_parameter("foobarbaz"); + node->declare_parameter("toto"); + auto parameters_client = std::make_shared(node); while (!parameters_client->wait_for_service(1s)) { if (!rclcpp::ok()) {