Skip to content

Declare parameters #241

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

Merged
merged 7 commits into from
Apr 23, 2019
Merged
Show file tree
Hide file tree
Changes from all 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
13 changes: 11 additions & 2 deletions demo_nodes_cpp/src/parameters/even_parameters_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,10 +26,19 @@ class EvenParameterNode : public rclcpp::Node
// Declare a parameter change request callback
// This function will enforce that only setting even integer parameters is allowed
// any other change will be discarded
auto existing_callback = this->set_on_parameters_set_callback(nullptr);
auto param_change_callback =
[this](std::vector<rclcpp::Parameter> parameters) -> rcl_interfaces::msg::SetParametersResult
[this, existing_callback](std::vector<rclcpp::Parameter> parameters)
{
auto result = rcl_interfaces::msg::SetParametersResult();
// first call the existing callback, if there was one
if (nullptr != existing_callback) {
result = existing_callback(parameters);
// if the existing callback failed, go ahead and return the result
if (!result.successful) {
return result;
}
}
result.successful = true;
for (auto parameter : parameters) {
rclcpp::ParameterType parameter_type = parameter.get_type();
Expand Down Expand Up @@ -67,7 +76,7 @@ class EvenParameterNode : public rclcpp::Node
}
return result;
};
this->register_param_change_callback(param_change_callback);
this->set_on_parameters_set_callback(param_change_callback);
}
};

Expand Down
8 changes: 8 additions & 0 deletions demo_nodes_cpp/src/parameters/list_parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,14 @@ int main(int argc, char ** argv)

auto node = rclcpp::Node::make_shared("list_parameters");

// Declare parameters that may be set on this node
node->declare_parameter("foo");
node->declare_parameter("bar");
node->declare_parameter("baz");
node->declare_parameter("foo.first");
node->declare_parameter("foo.second");
node->declare_parameter("foobar");

auto parameters_client = std::make_shared<rclcpp::SyncParametersClient>(node);
while (!parameters_client->wait_for_service(1s)) {
if (!rclcpp::ok()) {
Expand Down
9 changes: 9 additions & 0 deletions demo_nodes_cpp/src/parameters/list_parameters_async.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,16 @@ int main(int argc, char ** argv)

auto node = rclcpp::Node::make_shared("list_parameters_async");

// Declare parameters that may be set on this node
node->declare_parameter("foo");
node->declare_parameter("bar");
node->declare_parameter("baz");
node->declare_parameter("foo.first");
node->declare_parameter("foo.second");
node->declare_parameter("foobar");

auto parameters_client = std::make_shared<rclcpp::AsyncParametersClient>(node);

while (!parameters_client->wait_for_service(1s)) {
if (!rclcpp::ok()) {
RCLCPP_ERROR(node->get_logger(), "Interrupted while waiting for the service. Exiting.");
Expand Down
6 changes: 6 additions & 0 deletions demo_nodes_cpp/src/parameters/parameter_events.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,12 @@ int main(int argc, char ** argv)

auto node = rclcpp::Node::make_shared("parameter_events");

// Declare parameters that may be set on this node
node->declare_parameter("foo");
node->declare_parameter("bar");
node->declare_parameter("baz");
node->declare_parameter("foobar");

auto parameters_client = std::make_shared<rclcpp::SyncParametersClient>(node);
while (!parameters_client->wait_for_service(1s)) {
if (!rclcpp::ok()) {
Expand Down
6 changes: 6 additions & 0 deletions demo_nodes_cpp/src/parameters/parameter_events_async.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,12 @@ class ParameterEventsAsyncNode : public rclcpp::Node
ParameterEventsAsyncNode()
: Node("parameter_events")
{
// Declare parameters that may be set on this node
this->declare_parameter("foo");
this->declare_parameter("bar");
this->declare_parameter("baz");
this->declare_parameter("foobar");

// Typically a parameter client is created for a remote node by passing the name of the remote
// node in the constructor; in this example we create a parameter client for this node itself.
parameters_client_ = std::make_shared<rclcpp::AsyncParametersClient>(this);
Expand Down
8 changes: 8 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 @@ -29,6 +29,14 @@ int main(int argc, char ** argv)

auto node = rclcpp::Node::make_shared("set_and_get_parameters");

// Declare parameters that may be set on this node
node->declare_parameter("foo");
node->declare_parameter("bar");
node->declare_parameter("baz");
node->declare_parameter("foobar");
node->declare_parameter("foobarbaz");
node->declare_parameter("toto");

auto parameters_client = std::make_shared<rclcpp::SyncParametersClient>(node);
while (!parameters_client->wait_for_service(1s)) {
if (!rclcpp::ok()) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,14 @@ int main(int argc, char ** argv)

auto node = rclcpp::Node::make_shared("set_and_get_parameters_async");

// Declare parameters that may be set on this node
node->declare_parameter("foo");
node->declare_parameter("bar");
node->declare_parameter("baz");
node->declare_parameter("foobar");
node->declare_parameter("foobarbaz");
node->declare_parameter("toto");

auto parameters_client = std::make_shared<rclcpp::AsyncParametersClient>(node);
while (!parameters_client->wait_for_service(1s)) {
if (!rclcpp::ok()) {
Expand Down