From 22d89b9ba05bbfb38b389fb120ee31e76034f65b Mon Sep 17 00:00:00 2001 From: Shane Loretz Date: Thu, 31 May 2018 16:58:57 -0700 Subject: [PATCH] to_parameter_msg() from_parameter_msg() to_value_msg() --- rclcpp/include/rclcpp/parameter.hpp | 4 +- rclcpp/include/rclcpp/parameter_value.hpp | 2 +- .../node_interfaces/node_parameters.cpp | 6 +- rclcpp/src/rclcpp/parameter.cpp | 8 +-- rclcpp/src/rclcpp/parameter_client.cpp | 6 +- rclcpp/src/rclcpp/parameter_service.cpp | 4 +- rclcpp/src/rclcpp/parameter_value.cpp | 2 +- rclcpp/test/test_parameter.cpp | 58 +++++++++---------- 8 files changed, 45 insertions(+), 45 deletions(-) diff --git a/rclcpp/include/rclcpp/parameter.hpp b/rclcpp/include/rclcpp/parameter.hpp index 49332ae99a..2da788061c 100644 --- a/rclcpp/include/rclcpp/parameter.hpp +++ b/rclcpp/include/rclcpp/parameter.hpp @@ -114,11 +114,11 @@ class Parameter RCLCPP_PUBLIC static Parameter - from_parameter(const rcl_interfaces::msg::Parameter & parameter); + from_parameter_msg(const rcl_interfaces::msg::Parameter & parameter); RCLCPP_PUBLIC rcl_interfaces::msg::Parameter - to_parameter() const; + to_parameter_msg() const; RCLCPP_PUBLIC std::string diff --git a/rclcpp/include/rclcpp/parameter_value.hpp b/rclcpp/include/rclcpp/parameter_value.hpp index d6c6765400..197cbdf4a7 100644 --- a/rclcpp/include/rclcpp/parameter_value.hpp +++ b/rclcpp/include/rclcpp/parameter_value.hpp @@ -127,7 +127,7 @@ class ParameterValue /// Return a message populated with the parameter value RCLCPP_PUBLIC rcl_interfaces::msg::ParameterValue - get_message() const; + to_value_msg() const; // The following get() variants require the use of ParameterType diff --git a/rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp b/rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp index 7e5d4a399e..698330f4c6 100644 --- a/rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp +++ b/rclcpp/src/rclcpp/node_interfaces/node_parameters.cpp @@ -91,18 +91,18 @@ NodeParameters::set_parameters_atomically( if (parameters_.find(p.get_name()) == parameters_.end()) { if (p.get_type() != rclcpp::ParameterType::PARAMETER_NOT_SET) { // case: parameter not set before, and input is something other than "NOT_SET" - parameter_event->new_parameters.push_back(p.to_parameter()); + parameter_event->new_parameters.push_back(p.to_parameter_msg()); } } else if (p.get_type() != rclcpp::ParameterType::PARAMETER_NOT_SET) { // case: parameter was set before, and input is something other than "NOT_SET" - parameter_event->changed_parameters.push_back(p.to_parameter()); + parameter_event->changed_parameters.push_back(p.to_parameter_msg()); } else { // case: parameter was set before, and input is "NOT_SET" // therefore we will "unset" the previously set parameter // it is not necessary to erase the parameter from parameters_ // because the new value for this key (p.get_name()) will be a // Parameter with type "NOT_SET" - parameter_event->deleted_parameters.push_back(p.to_parameter()); + parameter_event->deleted_parameters.push_back(p.to_parameter_msg()); } tmp_map[p.get_name()] = p; } diff --git a/rclcpp/src/rclcpp/parameter.cpp b/rclcpp/src/rclcpp/parameter.cpp index 4b86b343d0..374a1ff550 100644 --- a/rclcpp/src/rclcpp/parameter.cpp +++ b/rclcpp/src/rclcpp/parameter.cpp @@ -54,7 +54,7 @@ Parameter::get_name() const rcl_interfaces::msg::ParameterValue Parameter::get_value_message() const { - return value_.get_message(); + return value_.to_value_msg(); } bool @@ -112,17 +112,17 @@ Parameter::as_string_array() const } Parameter -Parameter::from_parameter(const rcl_interfaces::msg::Parameter & parameter) +Parameter::from_parameter_msg(const rcl_interfaces::msg::Parameter & parameter) { return Parameter(parameter.name, parameter.value); } rcl_interfaces::msg::Parameter -Parameter::to_parameter() const +Parameter::to_parameter_msg() const { rcl_interfaces::msg::Parameter parameter; parameter.name = name_; - parameter.value = value_.get_message(); + parameter.value = value_.to_value_msg(); return parameter; } diff --git a/rclcpp/src/rclcpp/parameter_client.cpp b/rclcpp/src/rclcpp/parameter_client.cpp index 144d897502..d3b3287a62 100644 --- a/rclcpp/src/rclcpp/parameter_client.cpp +++ b/rclcpp/src/rclcpp/parameter_client.cpp @@ -141,7 +141,7 @@ AsyncParametersClient::get_parameters( rcl_interfaces::msg::Parameter parameter; parameter.name = request->names[i]; parameter.value = pvalue; - parameters.push_back(rclcpp::Parameter::from_parameter( + parameters.push_back(rclcpp::Parameter::from_parameter_msg( parameter)); } @@ -204,7 +204,7 @@ AsyncParametersClient::set_parameters( std::transform(parameters.begin(), parameters.end(), std::back_inserter(request->parameters), [](rclcpp::Parameter p) { - return p.to_parameter(); + return p.to_parameter_msg(); } ); @@ -238,7 +238,7 @@ AsyncParametersClient::set_parameters_atomically( std::transform(parameters.begin(), parameters.end(), std::back_inserter(request->parameters), [](rclcpp::Parameter p) { - return p.to_parameter(); + return p.to_parameter_msg(); } ); diff --git a/rclcpp/src/rclcpp/parameter_service.cpp b/rclcpp/src/rclcpp/parameter_service.cpp index fbe2c0a09e..b978524ade 100644 --- a/rclcpp/src/rclcpp/parameter_service.cpp +++ b/rclcpp/src/rclcpp/parameter_service.cpp @@ -72,7 +72,7 @@ ParameterService::ParameterService( { std::vector pvariants; for (auto & p : request->parameters) { - pvariants.push_back(rclcpp::Parameter::from_parameter(p)); + pvariants.push_back(rclcpp::Parameter::from_parameter_msg(p)); } auto results = node_params->set_parameters(pvariants); response->results = results; @@ -91,7 +91,7 @@ ParameterService::ParameterService( std::transform(request->parameters.cbegin(), request->parameters.cend(), std::back_inserter(pvariants), [](const rcl_interfaces::msg::Parameter & p) { - return rclcpp::Parameter::from_parameter(p); + return rclcpp::Parameter::from_parameter_msg(p); }); auto result = node_params->set_parameters_atomically(pvariants); response->result = result; diff --git a/rclcpp/src/rclcpp/parameter_value.cpp b/rclcpp/src/rclcpp/parameter_value.cpp index 0bd5518ed0..be3ecbe763 100644 --- a/rclcpp/src/rclcpp/parameter_value.cpp +++ b/rclcpp/src/rclcpp/parameter_value.cpp @@ -224,7 +224,7 @@ ParameterValue::get_type() const } rcl_interfaces::msg::ParameterValue -ParameterValue::get_message() const +ParameterValue::to_value_msg() const { return value_; } diff --git a/rclcpp/test/test_parameter.cpp b/rclcpp/test/test_parameter.cpp index e7e1ce634b..6f7a120d80 100644 --- a/rclcpp/test/test_parameter.cpp +++ b/rclcpp/test/test_parameter.cpp @@ -48,12 +48,12 @@ TEST(TestParameter, not_set_variant) { EXPECT_THROW(not_set_variant.as_double_array(), rclcpp::ParameterTypeException); EXPECT_THROW(not_set_variant.as_string_array(), rclcpp::ParameterTypeException); - rcl_interfaces::msg::Parameter not_set_param = not_set_variant.to_parameter(); + rcl_interfaces::msg::Parameter not_set_param = not_set_variant.to_parameter_msg(); EXPECT_EQ("", not_set_param.name); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_NOT_SET, not_set_param.value.type); // From parameter message - EXPECT_THROW(rclcpp::Parameter::from_parameter(not_set_param), + EXPECT_THROW(rclcpp::Parameter::from_parameter_msg(not_set_param), std::runtime_error); } @@ -86,14 +86,14 @@ TEST(TestParameter, bool_variant) { EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_BOOL, bool_variant_false.get_value_message().type); - rcl_interfaces::msg::Parameter bool_param = bool_variant_true.to_parameter(); + rcl_interfaces::msg::Parameter bool_param = bool_variant_true.to_parameter_msg(); EXPECT_EQ("bool_param", bool_param.name); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_BOOL, bool_param.value.type); EXPECT_TRUE(bool_param.value.bool_value); // From parameter message rclcpp::Parameter from_msg_true = - rclcpp::Parameter::from_parameter(bool_param); + rclcpp::Parameter::from_parameter_msg(bool_param); EXPECT_EQ("bool_param", from_msg_true.get_name()); EXPECT_EQ(rclcpp::ParameterType::PARAMETER_BOOL, from_msg_true.get_type()); EXPECT_EQ("bool", from_msg_true.get_type_name()); @@ -104,7 +104,7 @@ TEST(TestParameter, bool_variant) { bool_param.value.bool_value = false; rclcpp::Parameter from_msg_false = - rclcpp::Parameter::from_parameter(bool_param); + rclcpp::Parameter::from_parameter_msg(bool_param); EXPECT_FALSE(from_msg_false.get_value()); EXPECT_FALSE(from_msg_false.get_value_message().bool_value); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_BOOL, @@ -137,14 +137,14 @@ TEST(TestParameter, integer_variant) { EXPECT_EQ("42", integer_variant.value_to_string()); - rcl_interfaces::msg::Parameter integer_param = integer_variant.to_parameter(); + rcl_interfaces::msg::Parameter integer_param = integer_variant.to_parameter_msg(); EXPECT_EQ("integer_param", integer_param.name); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER, integer_param.value.type); EXPECT_EQ(TEST_VALUE, integer_param.value.integer_value); // From parameter message rclcpp::Parameter from_msg = - rclcpp::Parameter::from_parameter(integer_param); + rclcpp::Parameter::from_parameter_msg(integer_param); EXPECT_EQ("integer_param", from_msg.get_name()); EXPECT_EQ(rclcpp::ParameterType::PARAMETER_INTEGER, from_msg.get_type()); EXPECT_EQ("integer", from_msg.get_type_name()); @@ -181,14 +181,14 @@ TEST(TestParameter, long_integer_variant) { EXPECT_EQ("9223372036854775807", long_variant.value_to_string()); - rcl_interfaces::msg::Parameter integer_param = long_variant.to_parameter(); + rcl_interfaces::msg::Parameter integer_param = long_variant.to_parameter_msg(); EXPECT_EQ("long_integer_param", integer_param.name); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER, integer_param.value.type); EXPECT_EQ(TEST_VALUE, integer_param.value.integer_value); // From parameter message rclcpp::Parameter from_msg = - rclcpp::Parameter::from_parameter(integer_param); + rclcpp::Parameter::from_parameter_msg(integer_param); EXPECT_EQ("long_integer_param", from_msg.get_name()); EXPECT_EQ(rclcpp::ParameterType::PARAMETER_INTEGER, from_msg.get_type()); EXPECT_EQ("integer", from_msg.get_type_name()); @@ -225,14 +225,14 @@ TEST(TestParameter, float_variant) { EXPECT_EQ("42.000000", float_variant.value_to_string()); - rcl_interfaces::msg::Parameter float_param = float_variant.to_parameter(); + rcl_interfaces::msg::Parameter float_param = float_variant.to_parameter_msg(); EXPECT_EQ("float_param", float_param.name); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE, float_param.value.type); EXPECT_EQ(TEST_VALUE, float_param.value.double_value); // From parameter message rclcpp::Parameter from_msg = - rclcpp::Parameter::from_parameter(float_param); + rclcpp::Parameter::from_parameter_msg(float_param); EXPECT_EQ("float_param", from_msg.get_name()); EXPECT_EQ(rclcpp::ParameterType::PARAMETER_DOUBLE, from_msg.get_type()); EXPECT_EQ("double", from_msg.get_type_name()); @@ -269,14 +269,14 @@ TEST(TestParameter, double_variant) { EXPECT_EQ("-42.100000", double_variant.value_to_string()); - rcl_interfaces::msg::Parameter double_param = double_variant.to_parameter(); + rcl_interfaces::msg::Parameter double_param = double_variant.to_parameter_msg(); EXPECT_EQ("double_param", double_param.name); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE, double_param.value.type); EXPECT_EQ(TEST_VALUE, double_param.value.double_value); // From parameter message rclcpp::Parameter from_msg = - rclcpp::Parameter::from_parameter(double_param); + rclcpp::Parameter::from_parameter_msg(double_param); EXPECT_EQ("double_param", from_msg.get_name()); EXPECT_EQ(rclcpp::ParameterType::PARAMETER_DOUBLE, from_msg.get_type()); EXPECT_EQ("double", from_msg.get_type_name()); @@ -313,14 +313,14 @@ TEST(TestParameter, string_variant) { EXPECT_EQ(TEST_VALUE, string_variant.value_to_string()); - rcl_interfaces::msg::Parameter string_param = string_variant.to_parameter(); + rcl_interfaces::msg::Parameter string_param = string_variant.to_parameter_msg(); EXPECT_EQ("string_param", string_param.name); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_STRING, string_param.value.type); EXPECT_EQ(TEST_VALUE, string_param.value.string_value); // From parameter message rclcpp::Parameter from_msg = - rclcpp::Parameter::from_parameter(string_param); + rclcpp::Parameter::from_parameter_msg(string_param); EXPECT_EQ("string_param", from_msg.get_name()); EXPECT_EQ(rclcpp::ParameterType::PARAMETER_STRING, from_msg.get_type()); EXPECT_EQ("string", from_msg.get_type_name()); @@ -356,14 +356,14 @@ TEST(TestParameter, byte_array_variant) { EXPECT_EQ("[0x52, 0x4f, 0x53, 0x32]", byte_array_variant.value_to_string()); - rcl_interfaces::msg::Parameter byte_array_param = byte_array_variant.to_parameter(); + rcl_interfaces::msg::Parameter byte_array_param = byte_array_variant.to_parameter_msg(); EXPECT_EQ("byte_array_param", byte_array_param.name); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_BYTE_ARRAY, byte_array_param.value.type); EXPECT_EQ(TEST_VALUE, byte_array_param.value.byte_array_value); // From parameter message rclcpp::Parameter from_msg = - rclcpp::Parameter::from_parameter(byte_array_param); + rclcpp::Parameter::from_parameter_msg(byte_array_param); EXPECT_EQ("byte_array_param", from_msg.get_name()); EXPECT_EQ(rclcpp::ParameterType::PARAMETER_BYTE_ARRAY, from_msg.get_type()); EXPECT_EQ("byte_array", from_msg.get_type_name()); @@ -400,14 +400,14 @@ TEST(TestParameter, bool_array_variant) { EXPECT_EQ("[false, true, true, false, false, true]", bool_array_variant.value_to_string()); - rcl_interfaces::msg::Parameter bool_array_param = bool_array_variant.to_parameter(); + rcl_interfaces::msg::Parameter bool_array_param = bool_array_variant.to_parameter_msg(); EXPECT_EQ("bool_array_param", bool_array_param.name); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_BOOL_ARRAY, bool_array_param.value.type); EXPECT_EQ(TEST_VALUE, bool_array_param.value.bool_array_value); // From parameter message rclcpp::Parameter from_msg = - rclcpp::Parameter::from_parameter(bool_array_param); + rclcpp::Parameter::from_parameter_msg(bool_array_param); EXPECT_EQ("bool_array_param", from_msg.get_name()); EXPECT_EQ(rclcpp::ParameterType::PARAMETER_BOOL_ARRAY, from_msg.get_type()); EXPECT_EQ("bool_array", from_msg.get_type_name()); @@ -462,7 +462,7 @@ TEST(TestParameter, integer_array_variant) { "[42, -99, 2147483647, -2147483648, 0]", integer_array_variant.value_to_string()); - rcl_interfaces::msg::Parameter integer_array_param = integer_array_variant.to_parameter(); + rcl_interfaces::msg::Parameter integer_array_param = integer_array_variant.to_parameter_msg(); EXPECT_EQ("integer_array_param", integer_array_param.name); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER_ARRAY, integer_array_param.value.type); @@ -474,7 +474,7 @@ TEST(TestParameter, integer_array_variant) { // From parameter message rclcpp::Parameter from_msg = - rclcpp::Parameter::from_parameter(integer_array_param); + rclcpp::Parameter::from_parameter_msg(integer_array_param); EXPECT_EQ("integer_array_param", from_msg.get_name()); EXPECT_EQ(rclcpp::ParameterType::PARAMETER_INTEGER_ARRAY, from_msg.get_type()); EXPECT_EQ("integer_array", from_msg.get_type_name()); @@ -522,7 +522,7 @@ TEST(TestParameter, long_integer_array_variant) { "[42, -99, 9223372036854775807, -9223372036854775808, 0]", long_array_variant.value_to_string()); - rcl_interfaces::msg::Parameter integer_array_param = long_array_variant.to_parameter(); + rcl_interfaces::msg::Parameter integer_array_param = long_array_variant.to_parameter_msg(); EXPECT_EQ("long_integer_array_param", integer_array_param.name); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER_ARRAY, integer_array_param.value.type); @@ -530,7 +530,7 @@ TEST(TestParameter, long_integer_array_variant) { // From parameter message rclcpp::Parameter from_msg = - rclcpp::Parameter::from_parameter(integer_array_param); + rclcpp::Parameter::from_parameter_msg(integer_array_param); EXPECT_EQ("long_integer_array_param", from_msg.get_name()); EXPECT_EQ(rclcpp::ParameterType::PARAMETER_INTEGER_ARRAY, from_msg.get_type()); EXPECT_EQ("integer_array", from_msg.get_type_name()); @@ -585,7 +585,7 @@ TEST(TestParameter, float_array_variant) { "[42.1, -99.1, 3.40282e+38, -3.40282e+38, 0.1]", float_array_variant.value_to_string()); - rcl_interfaces::msg::Parameter float_array_param = float_array_variant.to_parameter(); + rcl_interfaces::msg::Parameter float_array_param = float_array_variant.to_parameter_msg(); EXPECT_EQ("float_array_param", float_array_param.name); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE_ARRAY, float_array_param.value.type); @@ -597,7 +597,7 @@ TEST(TestParameter, float_array_variant) { // From parameter message rclcpp::Parameter from_msg = - rclcpp::Parameter::from_parameter(float_array_param); + rclcpp::Parameter::from_parameter_msg(float_array_param); EXPECT_EQ("float_array_param", from_msg.get_name()); EXPECT_EQ(rclcpp::ParameterType::PARAMETER_DOUBLE_ARRAY, from_msg.get_type()); EXPECT_EQ("double_array", from_msg.get_type_name()); @@ -645,7 +645,7 @@ TEST(TestParameter, double_array_variant) { "[42.1, -99.1, 1.79769e+308, -1.79769e+308, 0.1]", double_array_variant.value_to_string()); - rcl_interfaces::msg::Parameter double_array_param = double_array_variant.to_parameter(); + rcl_interfaces::msg::Parameter double_array_param = double_array_variant.to_parameter_msg(); EXPECT_EQ("double_array_param", double_array_param.name); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE_ARRAY, double_array_param.value.type); @@ -653,7 +653,7 @@ TEST(TestParameter, double_array_variant) { // From parameter message rclcpp::Parameter from_msg = - rclcpp::Parameter::from_parameter(double_array_param); + rclcpp::Parameter::from_parameter_msg(double_array_param); EXPECT_EQ("double_array_param", from_msg.get_name()); EXPECT_EQ(rclcpp::ParameterType::PARAMETER_DOUBLE_ARRAY, from_msg.get_type()); EXPECT_EQ("double_array", from_msg.get_type_name()); @@ -691,7 +691,7 @@ TEST(TestParameter, string_array_variant) { EXPECT_EQ("[R, O, S2]", string_array_variant.value_to_string()); - rcl_interfaces::msg::Parameter string_array_param = string_array_variant.to_parameter(); + rcl_interfaces::msg::Parameter string_array_param = string_array_variant.to_parameter_msg(); EXPECT_EQ("string_array_param", string_array_param.name); EXPECT_EQ(rcl_interfaces::msg::ParameterType::PARAMETER_STRING_ARRAY, string_array_param.value.type); @@ -699,7 +699,7 @@ TEST(TestParameter, string_array_variant) { // From parameter message rclcpp::Parameter from_msg = - rclcpp::Parameter::from_parameter(string_array_param); + rclcpp::Parameter::from_parameter_msg(string_array_param); EXPECT_EQ("string_array_param", from_msg.get_name()); EXPECT_EQ(rclcpp::ParameterType::PARAMETER_STRING_ARRAY, from_msg.get_type()); EXPECT_EQ("string_array", from_msg.get_type_name());