Skip to content

Commit

Permalink
Use wait_for_service in parameter demos (#161)
Browse files Browse the repository at this point in the history
* Use wait_for_service in parameter demos

* remove extra semicolon

* Switch to printf
  • Loading branch information
dhood authored Aug 17, 2017
1 parent b7a64ab commit 79c2f5a
Show file tree
Hide file tree
Showing 10 changed files with 74 additions and 0 deletions.
11 changes: 11 additions & 0 deletions demo_nodes_cpp/src/parameters/list_parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,8 @@

#include "rclcpp/rclcpp.hpp"

using namespace std::chrono_literals;

int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);
Expand All @@ -27,7 +29,15 @@ int main(int argc, char ** argv)
auto parameter_service = std::make_shared<rclcpp::parameter_service::ParameterService>(node);

auto parameters_client = std::make_shared<rclcpp::parameter_client::SyncParametersClient>(node);
while (!parameters_client->wait_for_service(1s)) {
if (!rclcpp::ok()) {
printf("Interrupted while waiting for the service. Exiting.\n");
return 0;
}
printf("service not available, waiting again...\n");
}

printf("Setting parameters...\n");
// Set several differnet types of parameters.
auto set_parameters_results = parameters_client->set_parameters({
rclcpp::parameter::ParameterVariant("foo", 2),
Expand All @@ -38,6 +48,7 @@ int main(int argc, char ** argv)
rclcpp::parameter::ParameterVariant("foobar", true),
});

printf("Listing parameters...\n");
// List the details of a few parameters up to a namespace depth of 10.
auto parameters_and_prefixes = parameters_client->list_parameters({"foo", "bar"}, 10);
for (auto & name : parameters_and_prefixes.names) {
Expand Down
11 changes: 11 additions & 0 deletions demo_nodes_cpp/src/parameters/list_parameters_async.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,8 @@

#include "rclcpp/rclcpp.hpp"

using namespace std::chrono_literals;

int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);
Expand All @@ -27,7 +29,15 @@ int main(int argc, char ** argv)
auto parameter_service = std::make_shared<rclcpp::parameter_service::ParameterService>(node);

auto parameters_client = std::make_shared<rclcpp::parameter_client::AsyncParametersClient>(node);
while (!parameters_client->wait_for_service(1s)) {
if (!rclcpp::ok()) {
printf("Interrupted while waiting for the service. Exiting.\n");
return 0;
}
printf("service not available, waiting again...\n");
}

printf("Setting parameters...\n");
// Set several differnet types of parameters.
auto results = parameters_client->set_parameters({
rclcpp::parameter::ParameterVariant("foo", 2),
Expand All @@ -40,6 +50,7 @@ int main(int argc, char ** argv)
// Wait for the result.
rclcpp::spin_until_future_complete(node, results);

printf("Listing parameters...\n");
// List the details of a few parameters up to a namespace depth of 10.
auto parameter_list_future = parameters_client->list_parameters({"foo", "bar"}, 10);

Expand Down
7 changes: 7 additions & 0 deletions demo_nodes_cpp/src/parameters/parameter_events.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,13 @@ int main(int argc, char ** argv)
auto parameter_service = std::make_shared<rclcpp::parameter_service::ParameterService>(node);

auto parameters_client = std::make_shared<rclcpp::parameter_client::SyncParametersClient>(node);
while (!parameters_client->wait_for_service(1s)) {
if (!rclcpp::ok()) {
printf("Interrupted while waiting for the service. Exiting.\n");
return 0;
}
printf("service not available, waiting again...\n");
}

// Setup callback for changes to parameters.
auto sub = parameters_client->on_parameter_event(on_parameter_event);
Expand Down
7 changes: 7 additions & 0 deletions demo_nodes_cpp/src/parameters/parameter_events_async.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,13 @@ int main(int argc, char ** argv)
auto parameter_service = std::make_shared<rclcpp::parameter_service::ParameterService>(node);

auto parameters_client = std::make_shared<rclcpp::parameter_client::AsyncParametersClient>(node);
while (!parameters_client->wait_for_service(1s)) {
if (!rclcpp::ok()) {
printf("Interrupted while waiting for the service. Exiting.\n");
return 0;
}
printf("service not available, waiting again...\n");
}

// Setup callback for changes to parameters.
auto sub = parameters_client->on_parameter_event(on_parameter_event);
Expand Down
7 changes: 7 additions & 0 deletions demo_nodes_cpp/src/parameters/parameter_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,13 @@ int main(int argc, char ** argv)
auto parameter_service = std::make_shared<rclcpp::parameter_service::ParameterService>(node);

auto parameters_client = std::make_shared<rclcpp::parameter_client::SyncParametersClient>(node);
while (!parameters_client->wait_for_service(1s)) {
if (!rclcpp::ok()) {
printf("Interrupted while waiting for the service. Exiting.\n");
return 0;
}
printf("service not available, waiting again...\n");
}

// Setup callback for changes to parameters.
auto sub = parameters_client->on_parameter_event(on_parameter_event);
Expand Down
9 changes: 9 additions & 0 deletions demo_nodes_cpp/src/parameters/ros2param.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,8 @@

#include "rclcpp/rclcpp.hpp"

using namespace std::chrono_literals;

#define USAGE \
"USAGE:\n ros2param get <node/variable>\n ros2param set <node/variable> <value>\n" \
" ros2param list <node>"
Expand Down Expand Up @@ -104,6 +106,13 @@ int main(int argc, char ** argv)
auto parameters_client =
std::make_shared<rclcpp::parameter_client::AsyncParametersClient>(node, remote_node);
auto parameter_service = std::make_shared<rclcpp::parameter_service::ParameterService>(node);
while (!parameters_client->wait_for_service(1s)) {
if (!rclcpp::ok()) {
printf("Interrupted while waiting for the service. Exiting.\n");
return 0;
}
printf("service not available, waiting again...\n");
}

if (op == PARAM_GET) {
auto get_parameters_result = parameters_client->get_parameters({var.get_name()});
Expand Down
9 changes: 9 additions & 0 deletions demo_nodes_cpp/src/parameters/set_and_get_parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,8 @@

#include "rclcpp/rclcpp.hpp"

using namespace std::chrono_literals;

int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);
Expand All @@ -27,6 +29,13 @@ int main(int argc, char ** argv)
auto parameter_service = std::make_shared<rclcpp::parameter_service::ParameterService>(node);

auto parameters_client = std::make_shared<rclcpp::parameter_client::SyncParametersClient>(node);
while (!parameters_client->wait_for_service(1s)) {
if (!rclcpp::ok()) {
printf("Interrupted while waiting for the service. Exiting.\n");
return 0;
}
printf("service not available, waiting again...\n");
}

// Set several different types of parameters.
auto set_parameters_results = parameters_client->set_parameters({
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,8 @@

#include "rclcpp/rclcpp.hpp"

using namespace std::chrono_literals;

int main(int argc, char ** argv)
{
rclcpp::init(argc, argv);
Expand All @@ -27,6 +29,13 @@ int main(int argc, char ** argv)
auto parameter_service = std::make_shared<rclcpp::parameter_service::ParameterService>(node);

auto parameters_client = std::make_shared<rclcpp::parameter_client::AsyncParametersClient>(node);
while (!parameters_client->wait_for_service(1s)) {
if (!rclcpp::ok()) {
printf("Interrupted while waiting for the service. Exiting.\n");
return 0;
}
printf("service not available, waiting again...\n");
}

// Set several different types of parameters.
auto results = parameters_client->set_parameters({
Expand Down
2 changes: 2 additions & 0 deletions demo_nodes_cpp/test/list_parameters.txt
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
Setting parameters...
Listing parameters...
Parameter name: bar
Parameter name: foo
Parameter name: foo.first
Expand Down
2 changes: 2 additions & 0 deletions demo_nodes_cpp/test/list_parameters_async.txt
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
Setting parameters...
Listing parameters...
Parameter name: bar
Parameter name: foo
Parameter name: foo.first
Expand Down

0 comments on commit 79c2f5a

Please sign in to comment.