diff --git a/demo_nodes_cpp/src/parameters/list_parameters.cpp b/demo_nodes_cpp/src/parameters/list_parameters.cpp index 86a6e9c67..4d41c9df2 100644 --- a/demo_nodes_cpp/src/parameters/list_parameters.cpp +++ b/demo_nodes_cpp/src/parameters/list_parameters.cpp @@ -28,9 +28,6 @@ int main(int argc, char ** argv) auto node = rclcpp::Node::make_shared("list_parameters"); - // TODO(esteve): Make the parameter service automatically start with the node. - auto parameter_service = std::make_shared(node); - auto parameters_client = std::make_shared(node); while (!parameters_client->wait_for_service(1s)) { if (!rclcpp::ok()) { diff --git a/demo_nodes_cpp/src/parameters/list_parameters_async.cpp b/demo_nodes_cpp/src/parameters/list_parameters_async.cpp index 8f62c59f1..b64c82542 100644 --- a/demo_nodes_cpp/src/parameters/list_parameters_async.cpp +++ b/demo_nodes_cpp/src/parameters/list_parameters_async.cpp @@ -28,9 +28,6 @@ int main(int argc, char ** argv) auto node = rclcpp::Node::make_shared("list_parameters_async"); - // TODO(esteve): Make the parameter service automatically start with the node. - auto parameter_service = std::make_shared(node); - auto parameters_client = std::make_shared(node); while (!parameters_client->wait_for_service(1s)) { if (!rclcpp::ok()) { diff --git a/demo_nodes_cpp/src/parameters/parameter_events.cpp b/demo_nodes_cpp/src/parameters/parameter_events.cpp index a69de7af5..661e4e39d 100644 --- a/demo_nodes_cpp/src/parameters/parameter_events.cpp +++ b/demo_nodes_cpp/src/parameters/parameter_events.cpp @@ -50,9 +50,6 @@ int main(int argc, char ** argv) auto node = rclcpp::Node::make_shared("parameter_events"); - // TODO(esteve): Make the parameter service automatically start with the node. - auto parameter_service = std::make_shared(node); - auto parameters_client = std::make_shared(node); while (!parameters_client->wait_for_service(1s)) { if (!rclcpp::ok()) { diff --git a/demo_nodes_cpp/src/parameters/parameter_events_async.cpp b/demo_nodes_cpp/src/parameters/parameter_events_async.cpp index 359ff700d..e113889ee 100644 --- a/demo_nodes_cpp/src/parameters/parameter_events_async.cpp +++ b/demo_nodes_cpp/src/parameters/parameter_events_async.cpp @@ -133,8 +133,6 @@ int main(int argc, char ** argv) rclcpp::init(argc, argv); auto node = std::make_shared(); - // TODO(esteve): Make the parameter service automatically start with the node. - auto parameter_service = std::make_shared(node); rclcpp::spin(node); rclcpp::shutdown(); diff --git a/demo_nodes_cpp/src/parameters/parameter_node.cpp b/demo_nodes_cpp/src/parameters/parameter_node.cpp index 32374b4b9..660a041a3 100644 --- a/demo_nodes_cpp/src/parameters/parameter_node.cpp +++ b/demo_nodes_cpp/src/parameters/parameter_node.cpp @@ -62,8 +62,6 @@ int main(int argc, char ** argv) rclcpp::init(argc, argv); auto node = std::make_shared(); - // TODO(esteve): Make the parameter service automatically start with the node. - auto parameter_service = std::make_shared(node); rclcpp::spin(node); rclcpp::shutdown(); diff --git a/demo_nodes_cpp/src/parameters/ros2param.cpp b/demo_nodes_cpp/src/parameters/ros2param.cpp index c136a3768..6a5501521 100644 --- a/demo_nodes_cpp/src/parameters/ros2param.cpp +++ b/demo_nodes_cpp/src/parameters/ros2param.cpp @@ -108,7 +108,6 @@ int main(int argc, char ** argv) auto node = rclcpp::Node::make_shared("ros2param"); auto parameters_client = std::make_shared(node, remote_node); - auto parameter_service = std::make_shared(node); while (!parameters_client->wait_for_service(1s)) { if (!rclcpp::ok()) { RCLCPP_ERROR(node->get_logger(), "Interrupted while waiting for the service. Exiting.") diff --git a/demo_nodes_cpp/src/parameters/set_and_get_parameters.cpp b/demo_nodes_cpp/src/parameters/set_and_get_parameters.cpp index cc1ea259e..20f28ff0f 100644 --- a/demo_nodes_cpp/src/parameters/set_and_get_parameters.cpp +++ b/demo_nodes_cpp/src/parameters/set_and_get_parameters.cpp @@ -29,9 +29,6 @@ int main(int argc, char ** argv) auto node = rclcpp::Node::make_shared("set_and_get_parameters"); - // TODO(wjwwood): Make the parameter service automatically start with the node. - auto parameter_service = std::make_shared(node); - auto parameters_client = std::make_shared(node); while (!parameters_client->wait_for_service(1s)) { if (!rclcpp::ok()) { diff --git a/demo_nodes_cpp/src/parameters/set_and_get_parameters_async.cpp b/demo_nodes_cpp/src/parameters/set_and_get_parameters_async.cpp index 75d63461c..35e04dcbe 100644 --- a/demo_nodes_cpp/src/parameters/set_and_get_parameters_async.cpp +++ b/demo_nodes_cpp/src/parameters/set_and_get_parameters_async.cpp @@ -29,9 +29,6 @@ int main(int argc, char ** argv) auto node = rclcpp::Node::make_shared("set_and_get_parameters_async"); - // TODO(wjwwood): Make the parameter service automatically start with the node. - auto parameter_service = std::make_shared(node); - auto parameters_client = std::make_shared(node); while (!parameters_client->wait_for_service(1s)) { if (!rclcpp::ok()) {