Skip to content

Commit 1a7d944

Browse files
committed
wip: updating waitables to ensure things stay ready when needed, debugging code still there
Signed-off-by: William Woodall <[email protected]>
1 parent 633898f commit 1a7d944

16 files changed

+103
-1
lines changed

rclcpp/include/rclcpp/event_handler.hpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -106,6 +106,12 @@ class EventHandlerBase : public Waitable
106106
Event,
107107
};
108108

109+
// TODO(wjwwood): is this ok? do events continue to stay ready until they are
110+
// taken/checked?
111+
RCLCPP_PUBLIC
112+
void
113+
dummy() override {};
114+
109115
RCLCPP_PUBLIC
110116
virtual ~EventHandlerBase();
111117

rclcpp/include/rclcpp/executors/executor_notify_waitable.hpp

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -50,10 +50,13 @@ class ExecutorNotifyWaitable : public rclcpp::Waitable
5050
RCLCPP_PUBLIC
5151
ExecutorNotifyWaitable(const ExecutorNotifyWaitable & other);
5252

53-
5453
RCLCPP_PUBLIC
5554
ExecutorNotifyWaitable & operator=(const ExecutorNotifyWaitable & other);
5655

56+
RCLCPP_PUBLIC
57+
void
58+
dummy() override {};
59+
5760
/// Add conditions to the wait set
5861
/**
5962
* \param[inout] wait_set structure that conditions will be added to

rclcpp/include/rclcpp/executors/static_executor_entities_collector.hpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -53,6 +53,10 @@ class StaticExecutorEntitiesCollector final
5353
RCLCPP_PUBLIC
5454
~StaticExecutorEntitiesCollector();
5555

56+
RCLCPP_PUBLIC
57+
void
58+
dummy() override {};
59+
5660
/// Initialize StaticExecutorEntitiesCollector
5761
/**
5862
* \param p_wait_set A reference to the wait set to be used in the executor

rclcpp/include/rclcpp/experimental/subscription_intra_process.hpp

Lines changed: 22 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -101,6 +101,28 @@ class SubscriptionIntraProcess
101101

102102
virtual ~SubscriptionIntraProcess() = default;
103103

104+
RCLCPP_PUBLIC
105+
void
106+
dummy() override {};
107+
108+
RCLCPP_PUBLIC
109+
void
110+
add_to_wait_set(rcl_wait_set_t * wait_set) override
111+
{
112+
// This block is necessary when the guard condition wakes the wait set, but
113+
// the intra process waitable was not handled before the wait set is waited
114+
// on again.
115+
// Basically we're keeping the guard condition triggered so long as there is
116+
// data in the buffer.
117+
if (this->buffer_->has_data()) {
118+
// If there is data still to be processed, indicate to the
119+
// executor or waitset by triggering the guard condition.
120+
this->trigger_guard_condition();
121+
}
122+
// Let the parent classes handle the rest of the work:
123+
return SubscriptionIntraProcessBufferT::add_to_wait_set(wait_set);
124+
}
125+
104126
std::shared_ptr<void>
105127
take_data() override
106128
{

rclcpp/include/rclcpp/waitable.hpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -35,6 +35,11 @@ class Waitable
3535
RCLCPP_PUBLIC
3636
virtual ~Waitable() = default;
3737

38+
RCLCPP_PUBLIC
39+
virtual
40+
void
41+
dummy() = 0;
42+
3843
/// Get the number of ready subscriptions
3944
/**
4045
* Returns a value of 0 by default.

rclcpp/src/rclcpp/event_handler.cpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515
#include <stdexcept>
1616
#include <string>
1717

18+
#include "rcl/error_handling.h"
1819
#include "rcl/event.h"
1920

2021
#include "rclcpp/event_handler.hpp"

rclcpp/src/rclcpp/executors/executor_notify_waitable.cpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -47,6 +47,11 @@ ExecutorNotifyWaitable::add_to_wait_set(rcl_wait_set_t * wait_set)
4747
{
4848
std::lock_guard<std::mutex> lock(guard_condition_mutex_);
4949

50+
// Note: no guard conditions need to be re-triggered, since the guard
51+
// conditions in this class are not tracking a stateful condition, but instead
52+
// only serve to interrupt the wait set when new information is available to
53+
// consider.
54+
5055
for (auto weak_guard_condition : this->notify_guard_conditions_) {
5156
auto guard_condition = weak_guard_condition.lock();
5257
if (guard_condition) {

rclcpp/test/rclcpp/executors/test_executors.cpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -338,6 +338,12 @@ class TestWaitable : public rclcpp::Waitable
338338
public:
339339
TestWaitable() = default;
340340

341+
// TODO(wjwwood): is this ok? do events continue to stay ready until they are
342+
// taken/checked?
343+
RCLCPP_PUBLIC
344+
void
345+
dummy() override {};
346+
341347
void
342348
add_to_wait_set(rcl_wait_set_t * wait_set) override
343349
{

rclcpp/test/rclcpp/executors/test_static_executor_entities_collector.cpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -230,6 +230,12 @@ TEST_F(TestStaticExecutorEntitiesCollector, add_remove_node_out_of_scope) {
230230
class TestWaitable : public rclcpp::Waitable
231231
{
232232
public:
233+
// TODO(wjwwood): is this ok? do events continue to stay ready until they are
234+
// taken/checked?
235+
RCLCPP_PUBLIC
236+
void
237+
dummy() override {};
238+
233239
void add_to_wait_set(rcl_wait_set_t *) override {}
234240

235241
bool is_ready(rcl_wait_set_t *) override {return true;}

rclcpp/test/rclcpp/node_interfaces/test_node_waitables.cpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -28,6 +28,12 @@
2828
class TestWaitable : public rclcpp::Waitable
2929
{
3030
public:
31+
// TODO(wjwwood): is this ok? do events continue to stay ready until they are
32+
// taken/checked?
33+
RCLCPP_PUBLIC
34+
void
35+
dummy() override {};
36+
3137
void add_to_wait_set(rcl_wait_set_t *) override {}
3238
bool is_ready(rcl_wait_set_t *) override {return false;}
3339

0 commit comments

Comments
 (0)