Skip to content

Commit 05cb182

Browse files
committed
Revert "update rclcpp::Waitable API to use references and const (ros2#2467)"
This reverts commit c5bc4b6.
1 parent ba25a58 commit 05cb182

37 files changed

+140
-246
lines changed

rclcpp/include/rclcpp/event_handler.hpp

Lines changed: 3 additions & 3 deletions
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(const rcl_wait_set_t & wait_set) override;
125+
is_ready(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(const std::shared_ptr<void> & data) override
297+
execute(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

Lines changed: 3 additions & 3 deletions
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(const rcl_wait_set_t & wait_set) override;
72+
is_ready(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(const std::shared_ptr<void> & data) override;
81+
execute(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

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -132,22 +132,23 @@ class SubscriptionIntraProcess
132132
);
133133
}
134134

135-
void execute(const std::shared_ptr<void> & data) override
135+
void execute(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(const std::shared_ptr<void> &)
143+
execute_impl(std::shared_ptr<void> & data)
144144
{
145+
(void)data;
145146
throw std::runtime_error("Subscription intra-process can't handle serialized messages");
146147
}
147148

148149
template<class T>
149150
typename std::enable_if<!std::is_same<T, rcl_serialized_message_t>::value, void>::type
150-
execute_impl(const std::shared_ptr<void> & data)
151+
execute_impl(std::shared_ptr<void> & data)
151152
{
152153
if (!data) {
153154
return;

rclcpp/include/rclcpp/experimental/subscription_intra_process_base.hpp

Lines changed: 3 additions & 3 deletions
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(const rcl_wait_set_t & wait_set) override = 0;
75+
is_ready(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(const std::shared_ptr<void> & data) override = 0;
88+
execute(std::shared_ptr<void> & data) override = 0;
8989

9090
virtual
9191
bool

rclcpp/include/rclcpp/experimental/subscription_intra_process_buffer.hpp

Lines changed: 3 additions & 3 deletions
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(const rcl_wait_set_t & wait_set) override
113+
is_ready(rcl_wait_set_t * wait_set) override
114114
{
115115
(void) wait_set;
116116
return buffer_->has_data();

rclcpp/include/rclcpp/guard_condition.hpp

Lines changed: 2 additions & 4 deletions
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,9 +128,7 @@ 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-
// 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};
131+
rcl_wait_set_t * wait_set_{nullptr};
134132
};
135133

136134
} // namespace rclcpp

rclcpp/include/rclcpp/strategies/allocator_memory_strategy.hpp

Lines changed: 2 additions & 2 deletions
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

Lines changed: 1 addition & 1 deletion
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

Lines changed: 1 addition & 1 deletion
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

Lines changed: 3 additions & 54 deletions
Original file line numberDiff line numberDiff line change
@@ -101,23 +101,6 @@ 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-
121104
/// Add the Waitable to a wait set.
122105
/**
123106
* \param[in] wait_set A handle to the wait set to add the Waitable to.
@@ -126,24 +109,7 @@ class Waitable
126109
RCLCPP_PUBLIC
127110
virtual
128111
void
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
112+
add_to_wait_set(rcl_wait_set_t * wait_set) = 0;
147113

148114
/// Check if the Waitable is ready.
149115
/**
@@ -158,7 +124,7 @@ class Waitable
158124
RCLCPP_PUBLIC
159125
virtual
160126
bool
161-
is_ready(const rcl_wait_set_t & wait_set);
127+
is_ready(rcl_wait_set_t * wait_set) = 0;
162128

163129
/// Take the data so that it can be consumed with `execute`.
164130
/**
@@ -212,23 +178,6 @@ class Waitable
212178
std::shared_ptr<void>
213179
take_data_by_entity_id(size_t id);
214180

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-
232181
/// Execute data that is passed in.
233182
/**
234183
* Before calling this method, the Waitable should be added to a wait set,
@@ -254,7 +203,7 @@ class Waitable
254203
RCLCPP_PUBLIC
255204
virtual
256205
void
257-
execute(const std::shared_ptr<void> & data);
206+
execute(std::shared_ptr<void> & data) = 0;
258207

259208
/// Exchange the "in use by wait set" state for this timer.
260209
/**

0 commit comments

Comments
 (0)