From 19c00c784efa49bb9829b7bbcf18daa5331d7bdf Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Fri, 25 May 2018 16:02:47 -0700 Subject: [PATCH 1/2] Remove ::parameter:: from ParameterType --- demo_nodes_cpp/src/parameters/ros2param.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/demo_nodes_cpp/src/parameters/ros2param.cpp b/demo_nodes_cpp/src/parameters/ros2param.cpp index 6a5501521..8f1735ec5 100644 --- a/demo_nodes_cpp/src/parameters/ros2param.cpp +++ b/demo_nodes_cpp/src/parameters/ros2param.cpp @@ -122,22 +122,22 @@ int main(int argc, char ** argv) node, get_parameters_result, std::chrono::milliseconds(1000)); if ((get_result != rclcpp::executor::FutureReturnCode::SUCCESS) || (get_parameters_result.get().size() != 1) || - (get_parameters_result.get()[0].get_type() == rclcpp::parameter::PARAMETER_NOT_SET)) + (get_parameters_result.get()[0].get_type() == rclcpp::ParameterType::PARAMETER_NOT_SET)) { RCLCPP_ERROR(node->get_logger(), "Failed to get parameter") return 1; } auto result = get_parameters_result.get()[0]; - if (result.get_type() == rclcpp::parameter::PARAMETER_BOOL) { + if (result.get_type() == rclcpp::ParameterType::PARAMETER_BOOL) { RCLCPP_INFO(node->get_logger(), "%s", result.get_value() ? "true" : "false") - } else if (result.get_type() == rclcpp::parameter::PARAMETER_INTEGER) { + } else if (result.get_type() == rclcpp::ParameterType::PARAMETER_INTEGER) { RCLCPP_INFO(node->get_logger(), "%" PRId64, result.get_value()) - } else if (result.get_type() == rclcpp::parameter::PARAMETER_DOUBLE) { + } else if (result.get_type() == rclcpp::ParameterType::PARAMETER_DOUBLE) { RCLCPP_INFO(node->get_logger(), "%f", result.get_value()) - } else if (result.get_type() == rclcpp::parameter::PARAMETER_STRING) { + } else if (result.get_type() == rclcpp::ParameterType::PARAMETER_STRING) { RCLCPP_INFO(node->get_logger(), result.get_value().c_str()) - } else if (result.get_type() == rclcpp::parameter::PARAMETER_BYTE_ARRAY) { + } else if (result.get_type() == rclcpp::ParameterType::PARAMETER_BYTE_ARRAY) { RCLCPP_ERROR(node->get_logger(), "BYTES type not implemented") return 1; } From 43522e2c30f8f973e7fccf3df0ba5f0780a187d8 Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Tue, 29 May 2018 15:02:38 -0700 Subject: [PATCH 2/2] rclcpp::parameter::ParameterVariant -> rclcpp::Parameter --- .../src/parameters/list_parameters.cpp | 12 +++++----- .../src/parameters/list_parameters_async.cpp | 12 +++++----- .../src/parameters/parameter_events.cpp | 12 +++++----- .../src/parameters/parameter_events_async.cpp | 12 +++++----- demo_nodes_cpp/src/parameters/ros2param.cpp | 22 +++++++++---------- .../src/parameters/set_and_get_parameters.cpp | 12 +++++----- .../set_and_get_parameters_async.cpp | 12 +++++----- 7 files changed, 47 insertions(+), 47 deletions(-) diff --git a/demo_nodes_cpp/src/parameters/list_parameters.cpp b/demo_nodes_cpp/src/parameters/list_parameters.cpp index 4d41c9df2..564c96287 100644 --- a/demo_nodes_cpp/src/parameters/list_parameters.cpp +++ b/demo_nodes_cpp/src/parameters/list_parameters.cpp @@ -40,12 +40,12 @@ int main(int argc, char ** argv) RCLCPP_INFO(node->get_logger(), "Setting parameters...") // Set several differnet types of parameters. auto set_parameters_results = parameters_client->set_parameters({ - rclcpp::parameter::ParameterVariant("foo", 2), - rclcpp::parameter::ParameterVariant("bar", "hello"), - rclcpp::parameter::ParameterVariant("baz", 1.45), - rclcpp::parameter::ParameterVariant("foo.first", 8), - rclcpp::parameter::ParameterVariant("foo.second", 42), - rclcpp::parameter::ParameterVariant("foobar", true), + rclcpp::Parameter("foo", 2), + rclcpp::Parameter("bar", "hello"), + rclcpp::Parameter("baz", 1.45), + rclcpp::Parameter("foo.first", 8), + rclcpp::Parameter("foo.second", 42), + rclcpp::Parameter("foobar", true), }); RCLCPP_INFO(node->get_logger(), "Listing parameters...") diff --git a/demo_nodes_cpp/src/parameters/list_parameters_async.cpp b/demo_nodes_cpp/src/parameters/list_parameters_async.cpp index b64c82542..a4e60b30c 100644 --- a/demo_nodes_cpp/src/parameters/list_parameters_async.cpp +++ b/demo_nodes_cpp/src/parameters/list_parameters_async.cpp @@ -40,12 +40,12 @@ int main(int argc, char ** argv) RCLCPP_INFO(node->get_logger(), "Setting parameters...") // Set several differnet types of parameters. auto results = parameters_client->set_parameters({ - rclcpp::parameter::ParameterVariant("foo", 2), - rclcpp::parameter::ParameterVariant("bar", "hello"), - rclcpp::parameter::ParameterVariant("baz", 1.45), - rclcpp::parameter::ParameterVariant("foo.first", 8), - rclcpp::parameter::ParameterVariant("foo.second", 42), - rclcpp::parameter::ParameterVariant("foobar", true), + rclcpp::Parameter("foo", 2), + rclcpp::Parameter("bar", "hello"), + rclcpp::Parameter("baz", 1.45), + rclcpp::Parameter("foo.first", 8), + rclcpp::Parameter("foo.second", 42), + rclcpp::Parameter("foobar", true), }); // Wait for the result. rclcpp::spin_until_future_complete(node, results); diff --git a/demo_nodes_cpp/src/parameters/parameter_events.cpp b/demo_nodes_cpp/src/parameters/parameter_events.cpp index 661e4e39d..64b35c57e 100644 --- a/demo_nodes_cpp/src/parameters/parameter_events.cpp +++ b/demo_nodes_cpp/src/parameters/parameter_events.cpp @@ -68,16 +68,16 @@ int main(int argc, char ** argv) // Set several differnet types of parameters. auto set_parameters_results = parameters_client->set_parameters({ - rclcpp::parameter::ParameterVariant("foo", 2), - rclcpp::parameter::ParameterVariant("bar", "hello"), - rclcpp::parameter::ParameterVariant("baz", 1.45), - rclcpp::parameter::ParameterVariant("foobar", true), + rclcpp::Parameter("foo", 2), + rclcpp::Parameter("bar", "hello"), + rclcpp::Parameter("baz", 1.45), + rclcpp::Parameter("foobar", true), }); // Change the value of some of them. set_parameters_results = parameters_client->set_parameters({ - rclcpp::parameter::ParameterVariant("foo", 3), - rclcpp::parameter::ParameterVariant("bar", "world"), + rclcpp::Parameter("foo", 3), + rclcpp::Parameter("bar", "world"), }); // TODO(wjwwood): Create and use delete_parameter diff --git a/demo_nodes_cpp/src/parameters/parameter_events_async.cpp b/demo_nodes_cpp/src/parameters/parameter_events_async.cpp index e113889ee..693f044b2 100644 --- a/demo_nodes_cpp/src/parameters/parameter_events_async.cpp +++ b/demo_nodes_cpp/src/parameters/parameter_events_async.cpp @@ -88,10 +88,10 @@ class ParameterEventsAsyncNode : public rclcpp::Node }; parameters_client_->set_parameters({ - rclcpp::parameter::ParameterVariant("foo", 2), - rclcpp::parameter::ParameterVariant("bar", "hello"), - rclcpp::parameter::ParameterVariant("baz", 1.45), - rclcpp::parameter::ParameterVariant("foobar", true), + rclcpp::Parameter("foo", 2), + rclcpp::Parameter("bar", "hello"), + rclcpp::Parameter("baz", 1.45), + rclcpp::Parameter("foobar", true), }, response_received_callback); } @@ -114,8 +114,8 @@ class ParameterEventsAsyncNode : public rclcpp::Node }); }; parameters_client_->set_parameters({ - rclcpp::parameter::ParameterVariant("foo", 3), - rclcpp::parameter::ParameterVariant("bar", "world"), + rclcpp::Parameter("foo", 3), + rclcpp::Parameter("bar", "world"), }, response_received_callback); } diff --git a/demo_nodes_cpp/src/parameters/ros2param.cpp b/demo_nodes_cpp/src/parameters/ros2param.cpp index 8f1735ec5..1e51732e8 100644 --- a/demo_nodes_cpp/src/parameters/ros2param.cpp +++ b/demo_nodes_cpp/src/parameters/ros2param.cpp @@ -33,11 +33,11 @@ typedef enum PARAM_LIST, } param_operation_t; -rclcpp::parameter::ParameterVariant +rclcpp::Parameter parse_args(int argc, char ** argv, std::string & remote_node, param_operation_t & op) { if (argc < 3) { - return rclcpp::parameter::ParameterVariant(); + return rclcpp::Parameter(); } std::string verb = argv[1]; @@ -46,7 +46,7 @@ parse_args(int argc, char ** argv, std::string & remote_node, param_operation_t if (verb == "list") { op = PARAM_LIST; remote_node = name; - return rclcpp::parameter::ParameterVariant(); + return rclcpp::Parameter(); } size_t slash = name.find('/'); @@ -54,7 +54,7 @@ parse_args(int argc, char ** argv, std::string & remote_node, param_operation_t (slash == 0) || (slash == (name.size() - 1))) { - return rclcpp::parameter::ParameterVariant(); + return rclcpp::Parameter(); } remote_node = name.substr(0, slash); std::string variable = name.substr(slash + 1, name.size() - slash - 1); @@ -62,7 +62,7 @@ parse_args(int argc, char ** argv, std::string & remote_node, param_operation_t if ((verb == "get") && (argc == 3)) { op = PARAM_GET; - return rclcpp::parameter::ParameterVariant(variable, 0); + return rclcpp::Parameter(variable, 0); } if ((verb == "set") && (argc == 4)) { op = PARAM_SET; @@ -70,22 +70,22 @@ parse_args(int argc, char ** argv, std::string & remote_node, param_operation_t char * endptr; int l = strtol(value.c_str(), &endptr, 10); if ((errno == 0) && (*endptr == '\0')) { - return rclcpp::parameter::ParameterVariant(variable, l); + return rclcpp::Parameter(variable, l); } errno = 0; double d = strtod(value.c_str(), &endptr); if ((errno == 0) && (*endptr == '\0')) { - return rclcpp::parameter::ParameterVariant(variable, d); + return rclcpp::Parameter(variable, d); } if ((value == "true") || (value == "True")) { - return rclcpp::parameter::ParameterVariant(variable, true); + return rclcpp::Parameter(variable, true); } if ((value == "false") || (value == "False")) { - return rclcpp::parameter::ParameterVariant(variable, false); + return rclcpp::Parameter(variable, false); } - return rclcpp::parameter::ParameterVariant(variable, value); + return rclcpp::Parameter(variable, value); } - return rclcpp::parameter::ParameterVariant(); + return rclcpp::Parameter(); } int main(int argc, char ** argv) 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 20f28ff0f..22b33093f 100644 --- a/demo_nodes_cpp/src/parameters/set_and_get_parameters.cpp +++ b/demo_nodes_cpp/src/parameters/set_and_get_parameters.cpp @@ -40,12 +40,12 @@ int main(int argc, char ** argv) // Set several different types of parameters. auto set_parameters_results = parameters_client->set_parameters({ - rclcpp::parameter::ParameterVariant("foo", 2), - rclcpp::parameter::ParameterVariant("bar", "hello"), - rclcpp::parameter::ParameterVariant("baz", 1.45), - rclcpp::parameter::ParameterVariant("foobar", true), - rclcpp::parameter::ParameterVariant("foobarbaz", std::vector({true, false})), - rclcpp::parameter::ParameterVariant("toto", std::vector({0xff, 0x7f})), + rclcpp::Parameter("foo", 2), + rclcpp::Parameter("bar", "hello"), + rclcpp::Parameter("baz", 1.45), + rclcpp::Parameter("foobar", true), + rclcpp::Parameter("foobarbaz", std::vector({true, false})), + rclcpp::Parameter("toto", std::vector({0xff, 0x7f})), }); // Check to see if they were set. for (auto & result : set_parameters_results) { 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 35e04dcbe..20ffe5c7a 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 @@ -40,12 +40,12 @@ int main(int argc, char ** argv) // Set several different types of parameters. auto results = parameters_client->set_parameters({ - rclcpp::parameter::ParameterVariant("foo", 2), - rclcpp::parameter::ParameterVariant("bar", "hello"), - rclcpp::parameter::ParameterVariant("baz", 1.45), - rclcpp::parameter::ParameterVariant("foobar", true), - rclcpp::parameter::ParameterVariant("foobarbaz", std::vector({true, false})), - rclcpp::parameter::ParameterVariant("toto", std::vector({0xff, 0x7f})), + rclcpp::Parameter("foo", 2), + rclcpp::Parameter("bar", "hello"), + rclcpp::Parameter("baz", 1.45), + rclcpp::Parameter("foobar", true), + rclcpp::Parameter("foobarbaz", std::vector({true, false})), + rclcpp::Parameter("toto", std::vector({0xff, 0x7f})), }); // Wait for the results. if (rclcpp::spin_until_future_complete(node, results) !=