Skip to content

Commit 003348c

Browse files
authored
Use spin_until_future_complete instead of spin_some in parameters_event demo (#427)
Signed-off-by: Ivan Santiago Paunovic <[email protected]>
1 parent 53286a5 commit 003348c

File tree

1 file changed

+13
-8
lines changed

1 file changed

+13
-8
lines changed

demo_nodes_cpp/src/parameters/parameter_events.cpp

Lines changed: 13 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -13,8 +13,10 @@
1313
// limitations under the License.
1414

1515
#include <chrono>
16+
#include <future>
1617
#include <memory>
1718
#include <sstream>
19+
#include <utility>
1820

1921
#include "rclcpp/rclcpp.hpp"
2022

@@ -59,11 +61,20 @@ int main(int argc, char ** argv)
5961
RCLCPP_INFO(node->get_logger(), "service not available, waiting again...");
6062
}
6163

64+
auto events_received_promise = std::make_shared<std::promise<void>>();
65+
auto events_received_future = events_received_promise->get_future();
66+
6267
// Setup callback for changes to parameters.
6368
auto sub = parameters_client->on_parameter_event(
64-
[node](const rcl_interfaces::msg::ParameterEvent::SharedPtr event) -> void
69+
[node, promise = std::move(events_received_promise)](
70+
const rcl_interfaces::msg::ParameterEvent::SharedPtr event) -> void
6571
{
72+
static size_t n_times_called = 0u;
6673
on_parameter_event(event, node->get_logger());
74+
if (10u == ++n_times_called) {
75+
// This callback will be called 10 times, set the promise when that happens.
76+
promise->set_value();
77+
}
6778
});
6879

6980
// Declare parameters that may be set on this node
@@ -88,13 +99,7 @@ int main(int argc, char ** argv)
8899

89100
// TODO(wjwwood): Create and use delete_parameter
90101

91-
// TODO(hidmic): Fast-RTPS takes a significant amount of time to deliver
92-
// requests and response, thus the rather long sleep. Reduce
93-
// once that's resolved.
94-
rclcpp::sleep_for(3s);
95-
96-
rclcpp::spin_some(node);
97-
102+
rclcpp::spin_until_future_complete(node, events_received_future.share());
98103
rclcpp::shutdown();
99104

100105
return 0;

0 commit comments

Comments
 (0)