Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Use wait_for_service in parameter demos #161

Merged
merged 3 commits into from
Aug 17, 2017
Merged
Show file tree
Hide file tree
Changes from 2 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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()) {
std::cout << "Interrupted while waiting for the service. Exiting." << std::endl;
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Use printf.

Same below.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This entire file uses streams. If changing to printf, all prints should be updated. This can be done either here or in a separate PR

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I am not saying that the existing cout's need to be updated in this PR (though since it would only take a couple of minutes I think it would be good to do).

But newly added code should not use it.

return 0;
}
std::cout << "service not available, waiting again..." << std::endl;
}

std::cout << "Setting parameters..." << std::endl;
// 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),
});

std::cout << "Listing parameters..." << std::endl;
// 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()) {
std::cout << "Interrupted while waiting for the service. Exiting." << std::endl;
return 0;
}
std::cout << "service not available, waiting again..." << std::endl;
}

std::cout << "Setting parameters..." << std::endl;
// 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);

std::cout << "Listing parameters..." << std::endl;
// 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()) {
std::cout << "Interrupted while waiting for the service. Exiting." << std::endl;
return 0;
}
std::cout << "service not available, waiting again..." << std::endl;
}

// 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()) {
std::cout << "Interrupted while waiting for the service. Exiting." << std::endl;
return 0;
}
std::cout << "service not available, waiting again..." << std::endl;
}

// 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/parameter_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,11 +47,20 @@ 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()) {
std::cout << "Interrupted while waiting for the service. Exiting." << std::endl;
return 0;
}
std::cout << "service not available, waiting again..." << std::endl;
}

// Setup callback for changes to parameters.
auto sub = parameters_client->on_parameter_event(on_parameter_event);

rclcpp::spin(node);

rclcpp::shutdown();
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Should the other executables also call shutdown?

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

done in #162


return 0;
}
10 changes: 10 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()) {
std::cout << "Interrupted while waiting for the service. Exiting." << std::endl;
return 0;
}
std::cout << "service not available, waiting again..." << std::endl;
}

if (op == PARAM_GET) {
auto get_parameters_result = parameters_client->get_parameters({var.get_name()});
Expand Down Expand Up @@ -164,5 +173,6 @@ int main(int argc, char ** argv)
fprintf(stderr, "%s\n", USAGE);
return 1;
}
rclcpp::shutdown();
return 0;
}
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()) {
std::cout << "Interrupted while waiting for the service. Exiting." << std::endl;
return 0;
}
std::cout << "service not available, waiting again..." << std::endl;
}

// 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()) {
std::cout << "Interrupted while waiting for the service. Exiting." << std::endl;
return 0;
}
std::cout << "service not available, waiting again..." << std::endl;
}

// 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