Skip to content

Commit 3fa7416

Browse files
committed
add tests for waitables, fix const-ness in some of the APIs
Signed-off-by: William Woodall <[email protected]>
1 parent 670fc6d commit 3fa7416

20 files changed

+202
-34
lines changed

rclcpp/include/rclcpp/event_handler.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -122,7 +122,7 @@ class EventHandlerBase : public Waitable
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

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -68,7 +68,7 @@ class ExecutorNotifyWaitable : public rclcpp::Waitable
6868
*/
6969
RCLCPP_PUBLIC
7070
bool
71-
is_ready(rcl_wait_set_t * wait_set) override;
71+
is_ready(const rcl_wait_set_t * wait_set) override;
7272

7373
/// Perform work associated with the waitable.
7474
/**
@@ -77,7 +77,7 @@ class ExecutorNotifyWaitable : public rclcpp::Waitable
7777
*/
7878
RCLCPP_PUBLIC
7979
void
80-
execute(std::shared_ptr<void> & data) override;
80+
execute(const std::shared_ptr<void> & data) override;
8181

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

rclcpp/include/rclcpp/experimental/subscription_intra_process.hpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -150,25 +150,25 @@ class SubscriptionIntraProcess
150150
);
151151
}
152152

153-
void execute(std::shared_ptr<void> & data) override
153+
void execute(const std::shared_ptr<void> & data) override
154154
{
155155
execute_impl<SubscribedType>(data);
156156
}
157157

158158
protected:
159159
template<typename T>
160160
typename std::enable_if<std::is_same<T, rcl_serialized_message_t>::value, void>::type
161-
execute_impl(std::shared_ptr<void> & data)
161+
execute_impl(const std::shared_ptr<void> & data)
162162
{
163163
(void)data;
164164
throw std::runtime_error("Subscription intra-process can't handle serialized messages");
165165
}
166166

167167
template<class T>
168168
typename std::enable_if<!std::is_same<T, rcl_serialized_message_t>::value, void>::type
169-
execute_impl(std::shared_ptr<void> & data)
169+
execute_impl(const std::shared_ptr<void> & data)
170170
{
171-
if (!data) {
171+
if (nullptr == data) {
172172
return;
173173
}
174174

rclcpp/include/rclcpp/experimental/subscription_intra_process_base.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -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

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -110,7 +110,7 @@ class SubscriptionIntraProcessBuffer : public SubscriptionROSMsgIntraProcessBuff
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/waitable.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -124,7 +124,7 @@ class Waitable
124124
RCLCPP_PUBLIC
125125
virtual
126126
bool
127-
is_ready(rcl_wait_set_t * wait_set) = 0;
127+
is_ready(const rcl_wait_set_t * wait_set) = 0;
128128

129129
/// Take the data so that it can be consumed with `execute`.
130130
/**
@@ -203,7 +203,7 @@ class Waitable
203203
RCLCPP_PUBLIC
204204
virtual
205205
void
206-
execute(std::shared_ptr<void> & data) = 0;
206+
execute(const std::shared_ptr<void> & data) = 0;
207207

208208
/// Exchange the "in use by wait set" state for this timer.
209209
/**

rclcpp/src/rclcpp/event_handler.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -67,7 +67,7 @@ EventHandlerBase::add_to_wait_set(rcl_wait_set_t * wait_set)
6767

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

rclcpp/src/rclcpp/executors/executor_notify_waitable.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -69,7 +69,7 @@ ExecutorNotifyWaitable::add_to_wait_set(rcl_wait_set_t * wait_set)
6969
}
7070

7171
bool
72-
ExecutorNotifyWaitable::is_ready(rcl_wait_set_t * wait_set)
72+
ExecutorNotifyWaitable::is_ready(const rcl_wait_set_t * wait_set)
7373
{
7474
std::lock_guard<std::mutex> lock(guard_condition_mutex_);
7575

@@ -92,7 +92,7 @@ ExecutorNotifyWaitable::is_ready(rcl_wait_set_t * wait_set)
9292
}
9393

9494
void
95-
ExecutorNotifyWaitable::execute(std::shared_ptr<void> & data)
95+
ExecutorNotifyWaitable::execute(const std::shared_ptr<void> & data)
9696
{
9797
(void) data;
9898
this->execute_callback_();

rclcpp/test/rclcpp/CMakeLists.txt

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -566,6 +566,11 @@ if(TARGET test_thread_safe_synchronization)
566566
target_link_libraries(test_thread_safe_synchronization ${PROJECT_NAME} ${test_msgs_TARGETS})
567567
endif()
568568

569+
ament_add_gtest(test_intra_process_waitable waitables/test_intra_process_waitable.cpp)
570+
if(TARGET test_intra_process_waitable)
571+
target_link_libraries(test_intra_process_waitable ${PROJECT_NAME} ${test_msgs_TARGETS})
572+
endif()
573+
569574
ament_add_gtest(test_rosout_qos test_rosout_qos.cpp)
570575
if(TARGET test_rosout_qos)
571576
target_link_libraries(test_rosout_qos ${PROJECT_NAME} rcl::rcl rmw::rmw)

rclcpp/test/rclcpp/executors/test_executors.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -355,7 +355,7 @@ class TestWaitable : public rclcpp::Waitable
355355
}
356356

357357
bool
358-
is_ready(rcl_wait_set_t * wait_set) override
358+
is_ready(const rcl_wait_set_t * wait_set) override
359359
{
360360
(void)wait_set;
361361
return true;
@@ -375,7 +375,7 @@ class TestWaitable : public rclcpp::Waitable
375375
}
376376

377377
void
378-
execute(std::shared_ptr<void> & data) override
378+
execute(const std::shared_ptr<void> & data) override
379379
{
380380
(void) data;
381381
trigger_count_--;

0 commit comments

Comments
 (0)