Skip to content

Commit ccab9d9

Browse files
committed
Declare parameters
1 parent 3593af7 commit ccab9d9

6 files changed

+45
-0
lines changed

demo_nodes_cpp/src/parameters/list_parameters.cpp

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -28,6 +28,14 @@ int main(int argc, char ** argv)
2828

2929
auto node = rclcpp::Node::make_shared("list_parameters");
3030

31+
// Declare parameters that may be set on this node
32+
node->create_parameter("foo");
33+
node->create_parameter("bar");
34+
node->create_parameter("baz");
35+
node->create_parameter("foo.first");
36+
node->create_parameter("foo.second");
37+
node->create_parameter("foobar");
38+
3139
auto parameters_client = std::make_shared<rclcpp::SyncParametersClient>(node);
3240
while (!parameters_client->wait_for_service(1s)) {
3341
if (!rclcpp::ok()) {

demo_nodes_cpp/src/parameters/list_parameters_async.cpp

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -28,7 +28,16 @@ int main(int argc, char ** argv)
2828

2929
auto node = rclcpp::Node::make_shared("list_parameters_async");
3030

31+
// Declare parameters that may be set on this node
32+
node->create_parameter("foo");
33+
node->create_parameter("bar");
34+
node->create_parameter("baz");
35+
node->create_parameter("foo.first");
36+
node->create_parameter("foo.second");
37+
node->create_parameter("foobar");
38+
3139
auto parameters_client = std::make_shared<rclcpp::AsyncParametersClient>(node);
40+
3241
while (!parameters_client->wait_for_service(1s)) {
3342
if (!rclcpp::ok()) {
3443
RCLCPP_ERROR(node->get_logger(), "Interrupted while waiting for the service. Exiting.")

demo_nodes_cpp/src/parameters/parameter_events.cpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -50,6 +50,12 @@ int main(int argc, char ** argv)
5050

5151
auto node = rclcpp::Node::make_shared("parameter_events");
5252

53+
// Declare parameters that may be set on this node
54+
node->create_parameter("foo");
55+
node->create_parameter("bar");
56+
node->create_parameter("baz");
57+
node->create_parameter("foobar");
58+
5359
auto parameters_client = std::make_shared<rclcpp::SyncParametersClient>(node);
5460
while (!parameters_client->wait_for_service(1s)) {
5561
if (!rclcpp::ok()) {

demo_nodes_cpp/src/parameters/parameter_events_async.cpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -29,6 +29,12 @@ class ParameterEventsAsyncNode : public rclcpp::Node
2929
ParameterEventsAsyncNode()
3030
: Node("parameter_events")
3131
{
32+
// Declare parameters that may be set on this node
33+
create_parameter("foo");
34+
create_parameter("bar");
35+
create_parameter("baz");
36+
create_parameter("foobar");
37+
3238
// Typically a parameter client is created for a remote node by passing the name of the remote
3339
// node in the constructor; in this example we create a parameter client for this node itself.
3440
parameters_client_ = std::make_shared<rclcpp::AsyncParametersClient>(this);

demo_nodes_cpp/src/parameters/set_and_get_parameters.cpp

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -29,6 +29,14 @@ int main(int argc, char ** argv)
2929

3030
auto node = rclcpp::Node::make_shared("set_and_get_parameters");
3131

32+
// Declare parameters that may be set on this node
33+
node->create_parameter("foo");
34+
node->create_parameter("bar");
35+
node->create_parameter("baz");
36+
node->create_parameter("foobar");
37+
node->create_parameter("foobarbaz");
38+
node->create_parameter("toto");
39+
3240
auto parameters_client = std::make_shared<rclcpp::SyncParametersClient>(node);
3341
while (!parameters_client->wait_for_service(1s)) {
3442
if (!rclcpp::ok()) {

demo_nodes_cpp/src/parameters/set_and_get_parameters_async.cpp

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -29,6 +29,14 @@ int main(int argc, char ** argv)
2929

3030
auto node = rclcpp::Node::make_shared("set_and_get_parameters_async");
3131

32+
// Declare parameters that may be set on this node
33+
node->create_parameter("foo");
34+
node->create_parameter("bar");
35+
node->create_parameter("baz");
36+
node->create_parameter("foobar");
37+
node->create_parameter("foobarbaz");
38+
node->create_parameter("toto");
39+
3240
auto parameters_client = std::make_shared<rclcpp::AsyncParametersClient>(node);
3341
while (!parameters_client->wait_for_service(1s)) {
3442
if (!rclcpp::ok()) {

0 commit comments

Comments
 (0)