Skip to content

Commit

Permalink
replace create_parameter with declare_parameter
Browse files Browse the repository at this point in the history
Signed-off-by: William Woodall <william@osrfoundation.org>
  • Loading branch information
wjwwood committed Feb 19, 2019
1 parent 43e9a04 commit fd107e5
Show file tree
Hide file tree
Showing 6 changed files with 32 additions and 32 deletions.
12 changes: 6 additions & 6 deletions demo_nodes_cpp/src/parameters/list_parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<rclcpp::SyncParametersClient>(node);
while (!parameters_client->wait_for_service(1s)) {
Expand Down
12 changes: 6 additions & 6 deletions demo_nodes_cpp/src/parameters/list_parameters_async.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<rclcpp::AsyncParametersClient>(node);

Expand Down
8 changes: 4 additions & 4 deletions demo_nodes_cpp/src/parameters/parameter_events.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<rclcpp::SyncParametersClient>(node);
while (!parameters_client->wait_for_service(1s)) {
Expand Down
8 changes: 4 additions & 4 deletions demo_nodes_cpp/src/parameters/parameter_events_async.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand Down
12 changes: 6 additions & 6 deletions demo_nodes_cpp/src/parameters/set_and_get_parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<rclcpp::SyncParametersClient>(node);
while (!parameters_client->wait_for_service(1s)) {
Expand Down
12 changes: 6 additions & 6 deletions demo_nodes_cpp/src/parameters/set_and_get_parameters_async.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<rclcpp::AsyncParametersClient>(node);
while (!parameters_client->wait_for_service(1s)) {
Expand Down

0 comments on commit fd107e5

Please sign in to comment.