Skip to content

Commit b8207c0

Browse files
committed
replace create_parameter with declare_parameter
Signed-off-by: William Woodall <william@osrfoundation.org>
1 parent cdeb432 commit b8207c0

6 files changed

+32
-32
lines changed

demo_nodes_cpp/src/parameters/list_parameters.cpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -29,12 +29,12 @@ int main(int argc, char ** argv)
2929
auto node = rclcpp::Node::make_shared("list_parameters");
3030

3131
// 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");
32+
node->declare_parameter("foo");
33+
node->declare_parameter("bar");
34+
node->declare_parameter("baz");
35+
node->declare_parameter("foo.first");
36+
node->declare_parameter("foo.second");
37+
node->declare_parameter("foobar");
3838

3939
auto parameters_client = std::make_shared<rclcpp::SyncParametersClient>(node);
4040
while (!parameters_client->wait_for_service(1s)) {

demo_nodes_cpp/src/parameters/list_parameters_async.cpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -29,12 +29,12 @@ int main(int argc, char ** argv)
2929
auto node = rclcpp::Node::make_shared("list_parameters_async");
3030

3131
// 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");
32+
node->declare_parameter("foo");
33+
node->declare_parameter("bar");
34+
node->declare_parameter("baz");
35+
node->declare_parameter("foo.first");
36+
node->declare_parameter("foo.second");
37+
node->declare_parameter("foobar");
3838

3939
auto parameters_client = std::make_shared<rclcpp::AsyncParametersClient>(node);
4040

demo_nodes_cpp/src/parameters/parameter_events.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -51,10 +51,10 @@ int main(int argc, char ** argv)
5151
auto node = rclcpp::Node::make_shared("parameter_events");
5252

5353
// 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");
54+
node->declare_parameter("foo");
55+
node->declare_parameter("bar");
56+
node->declare_parameter("baz");
57+
node->declare_parameter("foobar");
5858

5959
auto parameters_client = std::make_shared<rclcpp::SyncParametersClient>(node);
6060
while (!parameters_client->wait_for_service(1s)) {

demo_nodes_cpp/src/parameters/parameter_events_async.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -30,10 +30,10 @@ class ParameterEventsAsyncNode : public rclcpp::Node
3030
: Node("parameter_events")
3131
{
3232
// 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");
33+
this->declare_parameter("foo");
34+
this->declare_parameter("bar");
35+
this->declare_parameter("baz");
36+
this->declare_parameter("foobar");
3737

3838
// Typically a parameter client is created for a remote node by passing the name of the remote
3939
// node in the constructor; in this example we create a parameter client for this node itself.

demo_nodes_cpp/src/parameters/set_and_get_parameters.cpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -30,12 +30,12 @@ int main(int argc, char ** argv)
3030
auto node = rclcpp::Node::make_shared("set_and_get_parameters");
3131

3232
// 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");
33+
node->declare_parameter("foo");
34+
node->declare_parameter("bar");
35+
node->declare_parameter("baz");
36+
node->declare_parameter("foobar");
37+
node->declare_parameter("foobarbaz");
38+
node->declare_parameter("toto");
3939

4040
auto parameters_client = std::make_shared<rclcpp::SyncParametersClient>(node);
4141
while (!parameters_client->wait_for_service(1s)) {

demo_nodes_cpp/src/parameters/set_and_get_parameters_async.cpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -30,12 +30,12 @@ int main(int argc, char ** argv)
3030
auto node = rclcpp::Node::make_shared("set_and_get_parameters_async");
3131

3232
// 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");
33+
node->declare_parameter("foo");
34+
node->declare_parameter("bar");
35+
node->declare_parameter("baz");
36+
node->declare_parameter("foobar");
37+
node->declare_parameter("foobarbaz");
38+
node->declare_parameter("toto");
3939

4040
auto parameters_client = std::make_shared<rclcpp::AsyncParametersClient>(node);
4141
while (!parameters_client->wait_for_service(1s)) {

0 commit comments

Comments
 (0)