Skip to content

Commit

Permalink
Split ParameterVariant (#237)
Browse files Browse the repository at this point in the history
* Remove ::parameter:: from ParameterType

* rclcpp::parameter::ParameterVariant -> rclcpp::Parameter
  • Loading branch information
sloretz authored Jun 1, 2018
1 parent 91ded04 commit 08e6f83
Show file tree
Hide file tree
Showing 7 changed files with 53 additions and 53 deletions.
12 changes: 6 additions & 6 deletions demo_nodes_cpp/src/parameters/list_parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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...")
Expand Down
12 changes: 6 additions & 6 deletions demo_nodes_cpp/src/parameters/list_parameters_async.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
12 changes: 6 additions & 6 deletions demo_nodes_cpp/src/parameters/parameter_events.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
12 changes: 6 additions & 6 deletions demo_nodes_cpp/src/parameters/parameter_events_async.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
}

Expand All @@ -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);
}

Expand Down
34 changes: 17 additions & 17 deletions demo_nodes_cpp/src/parameters/ros2param.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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];
Expand All @@ -46,46 +46,46 @@ 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('/');
if ((slash == std::string::npos) ||
(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);


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;
std::string value = argv[3];
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)
Expand Down Expand Up @@ -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<bool>() ? "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<int64_t>())
} 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<double>())
} 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<std::string>().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;
}
Expand Down
12 changes: 6 additions & 6 deletions demo_nodes_cpp/src/parameters/set_and_get_parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<bool>({true, false})),
rclcpp::parameter::ParameterVariant("toto", std::vector<uint8_t>({0xff, 0x7f})),
rclcpp::Parameter("foo", 2),
rclcpp::Parameter("bar", "hello"),
rclcpp::Parameter("baz", 1.45),
rclcpp::Parameter("foobar", true),
rclcpp::Parameter("foobarbaz", std::vector<bool>({true, false})),
rclcpp::Parameter("toto", std::vector<uint8_t>({0xff, 0x7f})),
});
// Check to see if they were set.
for (auto & result : set_parameters_results) {
Expand Down
12 changes: 6 additions & 6 deletions demo_nodes_cpp/src/parameters/set_and_get_parameters_async.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<bool>({true, false})),
rclcpp::parameter::ParameterVariant("toto", std::vector<uint8_t>({0xff, 0x7f})),
rclcpp::Parameter("foo", 2),
rclcpp::Parameter("bar", "hello"),
rclcpp::Parameter("baz", 1.45),
rclcpp::Parameter("foobar", true),
rclcpp::Parameter("foobarbaz", std::vector<bool>({true, false})),
rclcpp::Parameter("toto", std::vector<uint8_t>({0xff, 0x7f})),
});
// Wait for the results.
if (rclcpp::spin_until_future_complete(node, results) !=
Expand Down

0 comments on commit 08e6f83

Please sign in to comment.