From cdeb43236406ec2fa8b9d4282c18f20fd73790c7 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 8 Jun 2018 16:27:26 -0700 Subject: [PATCH 1/5] Declare parameters --- demo_nodes_cpp/src/parameters/list_parameters.cpp | 8 ++++++++ demo_nodes_cpp/src/parameters/list_parameters_async.cpp | 9 +++++++++ demo_nodes_cpp/src/parameters/parameter_events.cpp | 6 ++++++ demo_nodes_cpp/src/parameters/parameter_events_async.cpp | 6 ++++++ demo_nodes_cpp/src/parameters/set_and_get_parameters.cpp | 8 ++++++++ .../src/parameters/set_and_get_parameters_async.cpp | 8 ++++++++ 6 files changed, 45 insertions(+) diff --git a/demo_nodes_cpp/src/parameters/list_parameters.cpp b/demo_nodes_cpp/src/parameters/list_parameters.cpp index 07a703250..62dac96c6 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->create_parameter("foo"); + node->create_parameter("bar"); + node->create_parameter("baz"); + node->create_parameter("foo.first"); + node->create_parameter("foo.second"); + node->create_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..a9aed6589 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->create_parameter("foo"); + node->create_parameter("bar"); + node->create_parameter("baz"); + node->create_parameter("foo.first"); + node->create_parameter("foo.second"); + node->create_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..39916bc54 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->create_parameter("foo"); + node->create_parameter("bar"); + node->create_parameter("baz"); + node->create_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..6c2f302ef 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 + create_parameter("foo"); + create_parameter("bar"); + create_parameter("baz"); + create_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..08a507a89 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->create_parameter("foo"); + node->create_parameter("bar"); + node->create_parameter("baz"); + node->create_parameter("foobar"); + node->create_parameter("foobarbaz"); + node->create_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..e5861095c 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->create_parameter("foo"); + node->create_parameter("bar"); + node->create_parameter("baz"); + node->create_parameter("foobar"); + node->create_parameter("foobarbaz"); + node->create_parameter("toto"); + auto parameters_client = std::make_shared(node); while (!parameters_client->wait_for_service(1s)) { if (!rclcpp::ok()) { From b8207c0e1617e022fc2d7d95e03263b0c8ff32d2 Mon Sep 17 00:00:00 2001 From: William Woodall Date: Fri, 1 Feb 2019 08:48:04 -0800 Subject: [PATCH 2/5] replace create_parameter with declare_parameter Signed-off-by: William Woodall --- demo_nodes_cpp/src/parameters/list_parameters.cpp | 12 ++++++------ .../src/parameters/list_parameters_async.cpp | 12 ++++++------ demo_nodes_cpp/src/parameters/parameter_events.cpp | 8 ++++---- .../src/parameters/parameter_events_async.cpp | 8 ++++---- .../src/parameters/set_and_get_parameters.cpp | 12 ++++++------ .../src/parameters/set_and_get_parameters_async.cpp | 12 ++++++------ 6 files changed, 32 insertions(+), 32 deletions(-) diff --git a/demo_nodes_cpp/src/parameters/list_parameters.cpp b/demo_nodes_cpp/src/parameters/list_parameters.cpp index 62dac96c6..9aba49bb6 100644 --- a/demo_nodes_cpp/src/parameters/list_parameters.cpp +++ b/demo_nodes_cpp/src/parameters/list_parameters.cpp @@ -29,12 +29,12 @@ int main(int argc, char ** argv) auto node = rclcpp::Node::make_shared("list_parameters"); // Declare parameters that may be set on this node - node->create_parameter("foo"); - node->create_parameter("bar"); - node->create_parameter("baz"); - node->create_parameter("foo.first"); - node->create_parameter("foo.second"); - node->create_parameter("foobar"); + 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)) { diff --git a/demo_nodes_cpp/src/parameters/list_parameters_async.cpp b/demo_nodes_cpp/src/parameters/list_parameters_async.cpp index a9aed6589..d6430bdbc 100644 --- a/demo_nodes_cpp/src/parameters/list_parameters_async.cpp +++ b/demo_nodes_cpp/src/parameters/list_parameters_async.cpp @@ -29,12 +29,12 @@ 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->create_parameter("foo"); - node->create_parameter("bar"); - node->create_parameter("baz"); - node->create_parameter("foo.first"); - node->create_parameter("foo.second"); - node->create_parameter("foobar"); + 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); diff --git a/demo_nodes_cpp/src/parameters/parameter_events.cpp b/demo_nodes_cpp/src/parameters/parameter_events.cpp index 39916bc54..971705c20 100644 --- a/demo_nodes_cpp/src/parameters/parameter_events.cpp +++ b/demo_nodes_cpp/src/parameters/parameter_events.cpp @@ -51,10 +51,10 @@ int main(int argc, char ** argv) auto node = rclcpp::Node::make_shared("parameter_events"); // Declare parameters that may be set on this node - node->create_parameter("foo"); - node->create_parameter("bar"); - node->create_parameter("baz"); - node->create_parameter("foobar"); + 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)) { diff --git a/demo_nodes_cpp/src/parameters/parameter_events_async.cpp b/demo_nodes_cpp/src/parameters/parameter_events_async.cpp index 6c2f302ef..f7982dafa 100644 --- a/demo_nodes_cpp/src/parameters/parameter_events_async.cpp +++ b/demo_nodes_cpp/src/parameters/parameter_events_async.cpp @@ -30,10 +30,10 @@ class ParameterEventsAsyncNode : public rclcpp::Node : Node("parameter_events") { // Declare parameters that may be set on this node - create_parameter("foo"); - create_parameter("bar"); - create_parameter("baz"); - create_parameter("foobar"); + 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. 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 08a507a89..5d24bde22 100644 --- a/demo_nodes_cpp/src/parameters/set_and_get_parameters.cpp +++ b/demo_nodes_cpp/src/parameters/set_and_get_parameters.cpp @@ -30,12 +30,12 @@ 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->create_parameter("foo"); - node->create_parameter("bar"); - node->create_parameter("baz"); - node->create_parameter("foobar"); - node->create_parameter("foobarbaz"); - node->create_parameter("toto"); + 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)) { 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 e5861095c..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 @@ -30,12 +30,12 @@ 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->create_parameter("foo"); - node->create_parameter("bar"); - node->create_parameter("baz"); - node->create_parameter("foobar"); - node->create_parameter("foobarbaz"); - node->create_parameter("toto"); + 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)) { From 43e9a0442a75744fbea3264f2ded7d17a787342a Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 8 Jun 2018 16:27:26 -0700 Subject: [PATCH 3/5] Declare parameters --- demo_nodes_cpp/src/parameters/list_parameters.cpp | 8 ++++++++ demo_nodes_cpp/src/parameters/list_parameters_async.cpp | 9 +++++++++ demo_nodes_cpp/src/parameters/parameter_events.cpp | 6 ++++++ demo_nodes_cpp/src/parameters/parameter_events_async.cpp | 6 ++++++ demo_nodes_cpp/src/parameters/set_and_get_parameters.cpp | 8 ++++++++ .../src/parameters/set_and_get_parameters_async.cpp | 8 ++++++++ 6 files changed, 45 insertions(+) diff --git a/demo_nodes_cpp/src/parameters/list_parameters.cpp b/demo_nodes_cpp/src/parameters/list_parameters.cpp index 07a703250..62dac96c6 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->create_parameter("foo"); + node->create_parameter("bar"); + node->create_parameter("baz"); + node->create_parameter("foo.first"); + node->create_parameter("foo.second"); + node->create_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..a9aed6589 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->create_parameter("foo"); + node->create_parameter("bar"); + node->create_parameter("baz"); + node->create_parameter("foo.first"); + node->create_parameter("foo.second"); + node->create_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..39916bc54 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->create_parameter("foo"); + node->create_parameter("bar"); + node->create_parameter("baz"); + node->create_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..6c2f302ef 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 + create_parameter("foo"); + create_parameter("bar"); + create_parameter("baz"); + create_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..08a507a89 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->create_parameter("foo"); + node->create_parameter("bar"); + node->create_parameter("baz"); + node->create_parameter("foobar"); + node->create_parameter("foobarbaz"); + node->create_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..e5861095c 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->create_parameter("foo"); + node->create_parameter("bar"); + node->create_parameter("baz"); + node->create_parameter("foobar"); + node->create_parameter("foobarbaz"); + node->create_parameter("toto"); + auto parameters_client = std::make_shared(node); while (!parameters_client->wait_for_service(1s)) { if (!rclcpp::ok()) { From fd107e52a0a7bbf5d75ce8f2cef62d7aecbeb2b2 Mon Sep 17 00:00:00 2001 From: William Woodall Date: Fri, 1 Feb 2019 08:48:04 -0800 Subject: [PATCH 4/5] replace create_parameter with declare_parameter Signed-off-by: William Woodall --- demo_nodes_cpp/src/parameters/list_parameters.cpp | 12 ++++++------ .../src/parameters/list_parameters_async.cpp | 12 ++++++------ demo_nodes_cpp/src/parameters/parameter_events.cpp | 8 ++++---- .../src/parameters/parameter_events_async.cpp | 8 ++++---- .../src/parameters/set_and_get_parameters.cpp | 12 ++++++------ .../src/parameters/set_and_get_parameters_async.cpp | 12 ++++++------ 6 files changed, 32 insertions(+), 32 deletions(-) diff --git a/demo_nodes_cpp/src/parameters/list_parameters.cpp b/demo_nodes_cpp/src/parameters/list_parameters.cpp index 62dac96c6..9aba49bb6 100644 --- a/demo_nodes_cpp/src/parameters/list_parameters.cpp +++ b/demo_nodes_cpp/src/parameters/list_parameters.cpp @@ -29,12 +29,12 @@ int main(int argc, char ** argv) auto node = rclcpp::Node::make_shared("list_parameters"); // Declare parameters that may be set on this node - node->create_parameter("foo"); - node->create_parameter("bar"); - node->create_parameter("baz"); - node->create_parameter("foo.first"); - node->create_parameter("foo.second"); - node->create_parameter("foobar"); + 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)) { diff --git a/demo_nodes_cpp/src/parameters/list_parameters_async.cpp b/demo_nodes_cpp/src/parameters/list_parameters_async.cpp index a9aed6589..d6430bdbc 100644 --- a/demo_nodes_cpp/src/parameters/list_parameters_async.cpp +++ b/demo_nodes_cpp/src/parameters/list_parameters_async.cpp @@ -29,12 +29,12 @@ 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->create_parameter("foo"); - node->create_parameter("bar"); - node->create_parameter("baz"); - node->create_parameter("foo.first"); - node->create_parameter("foo.second"); - node->create_parameter("foobar"); + 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); diff --git a/demo_nodes_cpp/src/parameters/parameter_events.cpp b/demo_nodes_cpp/src/parameters/parameter_events.cpp index 39916bc54..971705c20 100644 --- a/demo_nodes_cpp/src/parameters/parameter_events.cpp +++ b/demo_nodes_cpp/src/parameters/parameter_events.cpp @@ -51,10 +51,10 @@ int main(int argc, char ** argv) auto node = rclcpp::Node::make_shared("parameter_events"); // Declare parameters that may be set on this node - node->create_parameter("foo"); - node->create_parameter("bar"); - node->create_parameter("baz"); - node->create_parameter("foobar"); + 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)) { diff --git a/demo_nodes_cpp/src/parameters/parameter_events_async.cpp b/demo_nodes_cpp/src/parameters/parameter_events_async.cpp index 6c2f302ef..f7982dafa 100644 --- a/demo_nodes_cpp/src/parameters/parameter_events_async.cpp +++ b/demo_nodes_cpp/src/parameters/parameter_events_async.cpp @@ -30,10 +30,10 @@ class ParameterEventsAsyncNode : public rclcpp::Node : Node("parameter_events") { // Declare parameters that may be set on this node - create_parameter("foo"); - create_parameter("bar"); - create_parameter("baz"); - create_parameter("foobar"); + 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. 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 08a507a89..5d24bde22 100644 --- a/demo_nodes_cpp/src/parameters/set_and_get_parameters.cpp +++ b/demo_nodes_cpp/src/parameters/set_and_get_parameters.cpp @@ -30,12 +30,12 @@ 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->create_parameter("foo"); - node->create_parameter("bar"); - node->create_parameter("baz"); - node->create_parameter("foobar"); - node->create_parameter("foobarbaz"); - node->create_parameter("toto"); + 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)) { 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 e5861095c..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 @@ -30,12 +30,12 @@ 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->create_parameter("foo"); - node->create_parameter("bar"); - node->create_parameter("baz"); - node->create_parameter("foobar"); - node->create_parameter("foobarbaz"); - node->create_parameter("toto"); + 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)) { From da305cd0cdedd0b37dee62e78afbf1229e4ce71a Mon Sep 17 00:00:00 2001 From: William Woodall Date: Thu, 18 Apr 2019 17:06:22 -0700 Subject: [PATCH 5/5] update to avoid deprecated API Signed-off-by: William Woodall --- .../src/parameters/even_parameters_node.cpp | 13 +++++++++++-- 1 file changed, 11 insertions(+), 2 deletions(-) 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); } };