Skip to content

Commit c5bc4b6

Browse files
authored
update rclcpp::Waitable API to use references and const (#2467)
Signed-off-by: William Woodall <[email protected]>
1 parent 5632a09 commit c5bc4b6

37 files changed

+246
-140
lines changed

rclcpp/include/rclcpp/event_handler.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -117,12 +117,12 @@ class EventHandlerBase : public Waitable
117117
/// Add the Waitable to a wait set.
118118
RCLCPP_PUBLIC
119119
void
120-
add_to_wait_set(rcl_wait_set_t * wait_set) override;
120+
add_to_wait_set(rcl_wait_set_t & wait_set) override;
121121

122122
/// Check if the Waitable is ready.
123123
RCLCPP_PUBLIC
124124
bool
125-
is_ready(rcl_wait_set_t * wait_set) override;
125+
is_ready(const rcl_wait_set_t & wait_set) override;
126126

127127
/// Set a callback to be called when each new event instance occurs.
128128
/**
@@ -294,7 +294,7 @@ class EventHandler : public EventHandlerBase
294294

295295
/// Execute any entities of the Waitable that are ready.
296296
void
297-
execute(std::shared_ptr<void> & data) override
297+
execute(const std::shared_ptr<void> & data) override
298298
{
299299
if (!data) {
300300
throw std::runtime_error("'data' is empty");

rclcpp/include/rclcpp/executors/executor_notify_waitable.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -60,7 +60,7 @@ class ExecutorNotifyWaitable : public rclcpp::Waitable
6060
*/
6161
RCLCPP_PUBLIC
6262
void
63-
add_to_wait_set(rcl_wait_set_t * wait_set) override;
63+
add_to_wait_set(rcl_wait_set_t & wait_set) override;
6464

6565
/// Check conditions against the wait set
6666
/**
@@ -69,7 +69,7 @@ class ExecutorNotifyWaitable : public rclcpp::Waitable
6969
*/
7070
RCLCPP_PUBLIC
7171
bool
72-
is_ready(rcl_wait_set_t * wait_set) override;
72+
is_ready(const rcl_wait_set_t & wait_set) override;
7373

7474
/// Perform work associated with the waitable.
7575
/**
@@ -78,7 +78,7 @@ class ExecutorNotifyWaitable : public rclcpp::Waitable
7878
*/
7979
RCLCPP_PUBLIC
8080
void
81-
execute(std::shared_ptr<void> & data) override;
81+
execute(const std::shared_ptr<void> & data) override;
8282

8383
/// Retrieve data to be used in the next execute call.
8484
/**

rclcpp/include/rclcpp/experimental/subscription_intra_process.hpp

+3-4
Original file line numberDiff line numberDiff line change
@@ -132,23 +132,22 @@ class SubscriptionIntraProcess
132132
);
133133
}
134134

135-
void execute(std::shared_ptr<void> & data) override
135+
void execute(const std::shared_ptr<void> & data) override
136136
{
137137
execute_impl<SubscribedType>(data);
138138
}
139139

140140
protected:
141141
template<typename T>
142142
typename std::enable_if<std::is_same<T, rcl_serialized_message_t>::value, void>::type
143-
execute_impl(std::shared_ptr<void> & data)
143+
execute_impl(const std::shared_ptr<void> &)
144144
{
145-
(void)data;
146145
throw std::runtime_error("Subscription intra-process can't handle serialized messages");
147146
}
148147

149148
template<class T>
150149
typename std::enable_if<!std::is_same<T, rcl_serialized_message_t>::value, void>::type
151-
execute_impl(std::shared_ptr<void> & data)
150+
execute_impl(const std::shared_ptr<void> & data)
152151
{
153152
if (!data) {
154153
return;

rclcpp/include/rclcpp/experimental/subscription_intra_process_base.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -60,7 +60,7 @@ class SubscriptionIntraProcessBase : public rclcpp::Waitable
6060

6161
RCLCPP_PUBLIC
6262
void
63-
add_to_wait_set(rcl_wait_set_t * wait_set) override;
63+
add_to_wait_set(rcl_wait_set_t & wait_set) override;
6464

6565
RCLCPP_PUBLIC
6666
virtual
@@ -72,7 +72,7 @@ class SubscriptionIntraProcessBase : public rclcpp::Waitable
7272
is_durability_transient_local() const;
7373

7474
bool
75-
is_ready(rcl_wait_set_t * wait_set) override = 0;
75+
is_ready(const rcl_wait_set_t & wait_set) override = 0;
7676

7777
std::shared_ptr<void>
7878
take_data() override = 0;
@@ -85,7 +85,7 @@ class SubscriptionIntraProcessBase : public rclcpp::Waitable
8585
}
8686

8787
void
88-
execute(std::shared_ptr<void> & data) override = 0;
88+
execute(const std::shared_ptr<void> & data) override = 0;
8989

9090
virtual
9191
bool

rclcpp/include/rclcpp/experimental/subscription_intra_process_buffer.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -101,16 +101,16 @@ class SubscriptionIntraProcessBuffer : public SubscriptionROSMsgIntraProcessBuff
101101
}
102102

103103
void
104-
add_to_wait_set(rcl_wait_set_t * wait_set) override
104+
add_to_wait_set(rcl_wait_set_t & wait_set) override
105105
{
106106
if (this->buffer_->has_data()) {
107107
this->trigger_guard_condition();
108108
}
109-
detail::add_guard_condition_to_rcl_wait_set(*wait_set, this->gc_);
109+
detail::add_guard_condition_to_rcl_wait_set(wait_set, this->gc_);
110110
}
111111

112112
bool
113-
is_ready(rcl_wait_set_t * wait_set) override
113+
is_ready(const rcl_wait_set_t & wait_set) override
114114
{
115115
(void) wait_set;
116116
return buffer_->has_data();

rclcpp/include/rclcpp/guard_condition.hpp

+4-2
Original file line numberDiff line numberDiff line change
@@ -100,7 +100,7 @@ class GuardCondition
100100
*/
101101
RCLCPP_PUBLIC
102102
void
103-
add_to_wait_set(rcl_wait_set_t * wait_set);
103+
add_to_wait_set(rcl_wait_set_t & wait_set);
104104

105105
/// Set a callback to be called whenever the guard condition is triggered.
106106
/**
@@ -128,7 +128,9 @@ class GuardCondition
128128
std::recursive_mutex reentrant_mutex_;
129129
std::function<void(size_t)> on_trigger_callback_{nullptr};
130130
size_t unread_count_{0};
131-
rcl_wait_set_t * wait_set_{nullptr};
131+
// the type of wait_set_ is actually rcl_wait_set_t *, but it's never
132+
// dereferenced, only compared to, so make it void * to avoid accidental use
133+
void * wait_set_{nullptr};
132134
};
133135

134136
} // namespace rclcpp

rclcpp/include/rclcpp/strategies/allocator_memory_strategy.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -121,7 +121,7 @@ class AllocatorMemoryStrategy : public memory_strategy::MemoryStrategy
121121
}
122122
}
123123
for (size_t i = 0; i < waitable_handles_.size(); ++i) {
124-
if (waitable_handles_[i]->is_ready(wait_set)) {
124+
if (waitable_handles_[i]->is_ready(*wait_set)) {
125125
waitable_triggered_handles_.emplace_back(std::move(waitable_handles_[i]));
126126
}
127127
}
@@ -235,7 +235,7 @@ class AllocatorMemoryStrategy : public memory_strategy::MemoryStrategy
235235
}
236236

237237
for (const std::shared_ptr<Waitable> & waitable : waitable_handles_) {
238-
waitable->add_to_wait_set(wait_set);
238+
waitable->add_to_wait_set(*wait_set);
239239
}
240240
return true;
241241
}

rclcpp/include/rclcpp/wait_result.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -277,7 +277,7 @@ class WaitResult final
277277
auto rcl_wait_set = wait_set.get_rcl_wait_set();
278278
while (next_waitable_index_ < wait_set.size_of_waitables()) {
279279
auto cur_waitable = wait_set.waitables(next_waitable_index_++);
280-
if (cur_waitable != nullptr && cur_waitable->is_ready(&rcl_wait_set)) {
280+
if (cur_waitable != nullptr && cur_waitable->is_ready(rcl_wait_set)) {
281281
waitable = cur_waitable;
282282
break;
283283
}

rclcpp/include/rclcpp/wait_set_policies/detail/storage_policy_common.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -375,7 +375,7 @@ class StoragePolicyCommon
375375
needs_pruning_ = true;
376376
continue;
377377
}
378-
waitable_entry.waitable->add_to_wait_set(&rcl_wait_set_);
378+
waitable_entry.waitable->add_to_wait_set(rcl_wait_set_);
379379
}
380380
}
381381

rclcpp/include/rclcpp/waitable.hpp

+54-3
Original file line numberDiff line numberDiff line change
@@ -101,6 +101,23 @@ class Waitable
101101
size_t
102102
get_number_of_ready_guard_conditions();
103103

104+
#ifdef __GNUC__
105+
#pragma GCC diagnostic push
106+
#pragma GCC diagnostic ignored "-Woverloaded-virtual"
107+
#endif
108+
/// Deprecated.
109+
/**
110+
* \sa add_to_wait_set(rcl_wait_set_t &)
111+
*/
112+
[[deprecated("Use add_to_wait_set(rcl_wait_set_t & wait_set) signature")]]
113+
RCLCPP_PUBLIC
114+
virtual
115+
void
116+
add_to_wait_set(rcl_wait_set_t * wait_set);
117+
#ifdef __GNUC__
118+
#pragma GCC diagnostic pop
119+
#endif
120+
104121
/// Add the Waitable to a wait set.
105122
/**
106123
* \param[in] wait_set A handle to the wait set to add the Waitable to.
@@ -109,7 +126,24 @@ class Waitable
109126
RCLCPP_PUBLIC
110127
virtual
111128
void
112-
add_to_wait_set(rcl_wait_set_t * wait_set) = 0;
129+
add_to_wait_set(rcl_wait_set_t & wait_set);
130+
131+
#ifdef __GNUC__
132+
#pragma GCC diagnostic push
133+
#pragma GCC diagnostic ignored "-Woverloaded-virtual"
134+
#endif
135+
/// Deprecated.
136+
/**
137+
* \sa is_ready(const rcl_wait_set_t &)
138+
*/
139+
[[deprecated("Use is_ready(const rcl_wait_set_t & wait_set) signature")]]
140+
RCLCPP_PUBLIC
141+
virtual
142+
bool
143+
is_ready(rcl_wait_set_t * wait_set);
144+
#ifdef __GNUC__
145+
#pragma GCC diagnostic pop
146+
#endif
113147

114148
/// Check if the Waitable is ready.
115149
/**
@@ -124,7 +158,7 @@ class Waitable
124158
RCLCPP_PUBLIC
125159
virtual
126160
bool
127-
is_ready(rcl_wait_set_t * wait_set) = 0;
161+
is_ready(const rcl_wait_set_t & wait_set);
128162

129163
/// Take the data so that it can be consumed with `execute`.
130164
/**
@@ -178,6 +212,23 @@ class Waitable
178212
std::shared_ptr<void>
179213
take_data_by_entity_id(size_t id);
180214

215+
#ifdef __GNUC__
216+
#pragma GCC diagnostic push
217+
#pragma GCC diagnostic ignored "-Woverloaded-virtual"
218+
#endif
219+
/// Deprecated.
220+
/**
221+
* \sa execute(const std::shared_ptr<void> &)
222+
*/
223+
[[deprecated("Use execute(const std::shared_ptr<void> & data) signature")]]
224+
RCLCPP_PUBLIC
225+
virtual
226+
void
227+
execute(std::shared_ptr<void> & data);
228+
#ifdef __GNUC__
229+
#pragma GCC diagnostic pop
230+
#endif
231+
181232
/// Execute data that is passed in.
182233
/**
183234
* Before calling this method, the Waitable should be added to a wait set,
@@ -203,7 +254,7 @@ class Waitable
203254
RCLCPP_PUBLIC
204255
virtual
205256
void
206-
execute(std::shared_ptr<void> & data) = 0;
257+
execute(const std::shared_ptr<void> & data);
207258

208259
/// Exchange the "in use by wait set" state for this timer.
209260
/**

rclcpp/src/rclcpp/event_handler.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -56,19 +56,19 @@ EventHandlerBase::get_number_of_ready_events()
5656

5757
/// Add the Waitable to a wait set.
5858
void
59-
EventHandlerBase::add_to_wait_set(rcl_wait_set_t * wait_set)
59+
EventHandlerBase::add_to_wait_set(rcl_wait_set_t & wait_set)
6060
{
61-
rcl_ret_t ret = rcl_wait_set_add_event(wait_set, &event_handle_, &wait_set_event_index_);
61+
rcl_ret_t ret = rcl_wait_set_add_event(&wait_set, &event_handle_, &wait_set_event_index_);
6262
if (RCL_RET_OK != ret) {
6363
exceptions::throw_from_rcl_error(ret, "Couldn't add event to wait set");
6464
}
6565
}
6666

6767
/// Check if the Waitable is ready.
6868
bool
69-
EventHandlerBase::is_ready(rcl_wait_set_t * wait_set)
69+
EventHandlerBase::is_ready(const rcl_wait_set_t & wait_set)
7070
{
71-
return wait_set->events[wait_set_event_index_] == &event_handle_;
71+
return wait_set.events[wait_set_event_index_] == &event_handle_;
7272
}
7373

7474
void

rclcpp/src/rclcpp/executor.cpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -398,7 +398,8 @@ Executor::execute_any_executable(AnyExecutable & any_exec)
398398
execute_client(any_exec.client);
399399
}
400400
if (any_exec.waitable) {
401-
any_exec.waitable->execute(any_exec.data);
401+
const std::shared_ptr<void> & const_data = any_exec.data;
402+
any_exec.waitable->execute(const_data);
402403
}
403404

404405
// Reset the callback_group, regardless of type

rclcpp/src/rclcpp/executors/executor_entities_collection.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -232,7 +232,7 @@ ready_executables(
232232
if (!waitable) {
233233
continue;
234234
}
235-
if (!waitable->is_ready(&rcl_wait_set)) {
235+
if (!waitable->is_ready(rcl_wait_set)) {
236236
continue;
237237
}
238238
auto group_info = group_cache(entry.callback_group);

rclcpp/src/rclcpp/executors/executor_notify_waitable.cpp

+6-7
Original file line numberDiff line numberDiff line change
@@ -45,16 +45,15 @@ ExecutorNotifyWaitable & ExecutorNotifyWaitable::operator=(ExecutorNotifyWaitabl
4545
}
4646

4747
void
48-
ExecutorNotifyWaitable::add_to_wait_set(rcl_wait_set_t * wait_set)
48+
ExecutorNotifyWaitable::add_to_wait_set(rcl_wait_set_t & wait_set)
4949
{
5050
std::lock_guard<std::mutex> lock(guard_condition_mutex_);
5151
for (auto weak_guard_condition : this->notify_guard_conditions_) {
5252
auto guard_condition = weak_guard_condition.lock();
5353
if (!guard_condition) {continue;}
5454

5555
rcl_guard_condition_t * cond = &guard_condition->get_rcl_guard_condition();
56-
57-
rcl_ret_t ret = rcl_wait_set_add_guard_condition(wait_set, cond, NULL);
56+
rcl_ret_t ret = rcl_wait_set_add_guard_condition(&wait_set, cond, NULL);
5857

5958
if (RCL_RET_OK != ret) {
6059
rclcpp::exceptions::throw_from_rcl_error(
@@ -64,13 +63,13 @@ ExecutorNotifyWaitable::add_to_wait_set(rcl_wait_set_t * wait_set)
6463
}
6564

6665
bool
67-
ExecutorNotifyWaitable::is_ready(rcl_wait_set_t * wait_set)
66+
ExecutorNotifyWaitable::is_ready(const rcl_wait_set_t & wait_set)
6867
{
6968
std::lock_guard<std::mutex> lock(guard_condition_mutex_);
7069

7170
bool any_ready = false;
72-
for (size_t ii = 0; ii < wait_set->size_of_guard_conditions; ++ii) {
73-
const auto * rcl_guard_condition = wait_set->guard_conditions[ii];
71+
for (size_t ii = 0; ii < wait_set.size_of_guard_conditions; ++ii) {
72+
const auto * rcl_guard_condition = wait_set.guard_conditions[ii];
7473

7574
if (nullptr == rcl_guard_condition) {
7675
continue;
@@ -87,7 +86,7 @@ ExecutorNotifyWaitable::is_ready(rcl_wait_set_t * wait_set)
8786
}
8887

8988
void
90-
ExecutorNotifyWaitable::execute(std::shared_ptr<void> & data)
89+
ExecutorNotifyWaitable::execute(const std::shared_ptr<void> & data)
9190
{
9291
(void) data;
9392
this->execute_callback_();

rclcpp/src/rclcpp/executors/static_single_threaded_executor.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -183,7 +183,7 @@ bool StaticSingleThreadedExecutor::execute_ready_executables(
183183
while (auto waitable = wait_result.next_ready_waitable()) {
184184
auto entity_iter = collection.waitables.find(waitable.get());
185185
if (entity_iter != collection.waitables.end()) {
186-
auto data = waitable->take_data();
186+
const auto data = waitable->take_data();
187187
waitable->execute(data);
188188
any_ready_executable = true;
189189
if (spin_once) {return any_ready_executable;}

rclcpp/src/rclcpp/experimental/executors/events_executor/events_executor.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -339,7 +339,7 @@ EventsExecutor::execute_event(const ExecutorEvent & event)
339339
}
340340
if (waitable) {
341341
for (size_t i = 0; i < event.num_events; i++) {
342-
auto data = waitable->take_data_by_entity_id(event.waitable_data);
342+
const auto data = waitable->take_data_by_entity_id(event.waitable_data);
343343
waitable->execute(data);
344344
}
345345
}

0 commit comments

Comments
 (0)