Skip to content

Commit

Permalink
add tests for waitables, fix const-ness in some of the APIs
Browse files Browse the repository at this point in the history
Signed-off-by: William Woodall <william@osrfoundation.org>
  • Loading branch information
wjwwood committed Mar 27, 2024
1 parent 3fdd4ef commit bf03d2f
Show file tree
Hide file tree
Showing 22 changed files with 206 additions and 38 deletions.
4 changes: 2 additions & 2 deletions rclcpp/include/rclcpp/event_handler.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -122,7 +122,7 @@ class EventHandlerBase : public Waitable
/// Check if the Waitable is ready.
RCLCPP_PUBLIC
bool
is_ready(rcl_wait_set_t * wait_set) override;
is_ready(const rcl_wait_set_t * wait_set) override;

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

/// Execute any entities of the Waitable that are ready.
void
execute(std::shared_ptr<void> & data) override
execute(const std::shared_ptr<void> & data) override
{
if (!data) {
throw std::runtime_error("'data' is empty");
Expand Down
4 changes: 2 additions & 2 deletions rclcpp/include/rclcpp/executors/executor_notify_waitable.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ class ExecutorNotifyWaitable : public rclcpp::Waitable
*/
RCLCPP_PUBLIC
bool
is_ready(rcl_wait_set_t * wait_set) override;
is_ready(const rcl_wait_set_t * wait_set) override;

/// Perform work associated with the waitable.
/**
Expand All @@ -77,7 +77,7 @@ class ExecutorNotifyWaitable : public rclcpp::Waitable
*/
RCLCPP_PUBLIC
void
execute(std::shared_ptr<void> & data) override;
execute(const std::shared_ptr<void> & data) override;

/// Retrieve data to be used in the next execute call.
/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,7 @@ class StaticExecutorEntitiesCollector final
/// Execute the waitable.
RCLCPP_PUBLIC
void
execute(std::shared_ptr<void> & data) override;
execute(const std::shared_ptr<void> & data) override;

/// Take the data so that it can be consumed with `execute`.
/**
Expand Down Expand Up @@ -196,7 +196,7 @@ class StaticExecutorEntitiesCollector final
*/
RCLCPP_PUBLIC
bool
is_ready(rcl_wait_set_t * wait_set) override;
is_ready(const rcl_wait_set_t * wait_set) override;

/// Return number of timers
/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -150,25 +150,25 @@ class SubscriptionIntraProcess
);
}

void execute(std::shared_ptr<void> & data) override
void execute(const std::shared_ptr<void> & data) override
{
execute_impl<SubscribedType>(data);
}

protected:
template<typename T>
typename std::enable_if<std::is_same<T, rcl_serialized_message_t>::value, void>::type
execute_impl(std::shared_ptr<void> & data)
execute_impl(const std::shared_ptr<void> & data)
{
(void)data;
throw std::runtime_error("Subscription intra-process can't handle serialized messages");
}

template<class T>
typename std::enable_if<!std::is_same<T, rcl_serialized_message_t>::value, void>::type
execute_impl(std::shared_ptr<void> & data)
execute_impl(const std::shared_ptr<void> & data)
{
if (!data) {
if (nullptr == data) {
return;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ class SubscriptionIntraProcessBase : public rclcpp::Waitable
is_durability_transient_local() const;

bool
is_ready(rcl_wait_set_t * wait_set) override = 0;
is_ready(const rcl_wait_set_t * wait_set) override = 0;

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

void
execute(std::shared_ptr<void> & data) override = 0;
execute(const std::shared_ptr<void> & data) override = 0;

virtual
bool
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -100,7 +100,7 @@ class SubscriptionIntraProcessBuffer : public SubscriptionROSMsgIntraProcessBuff
}

bool
is_ready(rcl_wait_set_t * wait_set) override
is_ready(const rcl_wait_set_t * wait_set) override
{
(void) wait_set;
return buffer_->has_data();
Expand Down
4 changes: 2 additions & 2 deletions rclcpp/include/rclcpp/waitable.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -124,7 +124,7 @@ class Waitable
RCLCPP_PUBLIC
virtual
bool
is_ready(rcl_wait_set_t * wait_set) = 0;
is_ready(const rcl_wait_set_t * wait_set) = 0;

/// Take the data so that it can be consumed with `execute`.
/**
Expand Down Expand Up @@ -203,7 +203,7 @@ class Waitable
RCLCPP_PUBLIC
virtual
void
execute(std::shared_ptr<void> & data) = 0;
execute(const std::shared_ptr<void> & data) = 0;

/// Exchange the "in use by wait set" state for this timer.
/**
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/src/rclcpp/event_handler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ EventHandlerBase::add_to_wait_set(rcl_wait_set_t * wait_set)

/// Check if the Waitable is ready.
bool
EventHandlerBase::is_ready(rcl_wait_set_t * wait_set)
EventHandlerBase::is_ready(const rcl_wait_set_t * wait_set)
{
return wait_set->events[wait_set_event_index_] == &event_handle_;
}
Expand Down
4 changes: 2 additions & 2 deletions rclcpp/src/rclcpp/executors/executor_notify_waitable.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ ExecutorNotifyWaitable::add_to_wait_set(rcl_wait_set_t * wait_set)
}

bool
ExecutorNotifyWaitable::is_ready(rcl_wait_set_t * wait_set)
ExecutorNotifyWaitable::is_ready(const rcl_wait_set_t * wait_set)
{
std::lock_guard<std::mutex> lock(guard_condition_mutex_);

Expand All @@ -92,7 +92,7 @@ ExecutorNotifyWaitable::is_ready(rcl_wait_set_t * wait_set)
}

void
ExecutorNotifyWaitable::execute(std::shared_ptr<void> & data)
ExecutorNotifyWaitable::execute(const std::shared_ptr<void> & data)
{
(void) data;
this->execute_callback_();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -96,7 +96,7 @@ StaticExecutorEntitiesCollector::take_data()
}

void
StaticExecutorEntitiesCollector::execute(std::shared_ptr<void> & data)
StaticExecutorEntitiesCollector::execute(const std::shared_ptr<void> & data)
{
(void) data;
// Fill memory strategy with entities coming from weak_nodes_
Expand Down Expand Up @@ -434,7 +434,7 @@ StaticExecutorEntitiesCollector::remove_node(
}

bool
StaticExecutorEntitiesCollector::is_ready(rcl_wait_set_t * p_wait_set)
StaticExecutorEntitiesCollector::is_ready(const rcl_wait_set_t * p_wait_set)
{
// Check wait_set guard_conditions for added/removed entities to/from a node
for (size_t i = 0; i < p_wait_set->size_of_guard_conditions; ++i) {
Expand Down
5 changes: 5 additions & 0 deletions rclcpp/test/rclcpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -572,6 +572,11 @@ if(TARGET test_thread_safe_synchronization)
target_link_libraries(test_thread_safe_synchronization ${PROJECT_NAME} ${test_msgs_TARGETS})
endif()

ament_add_gtest(test_intra_process_waitable waitables/test_intra_process_waitable.cpp)
if(TARGET test_intra_process_waitable)
target_link_libraries(test_intra_process_waitable ${PROJECT_NAME} ${test_msgs_TARGETS})
endif()

ament_add_gtest(test_rosout_qos test_rosout_qos.cpp)
if(TARGET test_rosout_qos)
target_link_libraries(test_rosout_qos ${PROJECT_NAME} rcl::rcl rmw::rmw)
Expand Down
4 changes: 2 additions & 2 deletions rclcpp/test/rclcpp/executors/test_executors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -350,7 +350,7 @@ class TestWaitable : public rclcpp::Waitable
}

bool
is_ready(rcl_wait_set_t * wait_set) override
is_ready(const rcl_wait_set_t * wait_set) override
{
for (size_t i = 0; i < wait_set->size_of_guard_conditions; ++i) {
auto rcl_guard_condition = wait_set->guard_conditions[i];
Expand All @@ -375,7 +375,7 @@ class TestWaitable : public rclcpp::Waitable
}

void
execute(std::shared_ptr<void> & data) override
execute(const std::shared_ptr<void> & data) override
{
(void) data;
count_++;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -232,15 +232,15 @@ class TestWaitable : public rclcpp::Waitable
public:
void add_to_wait_set(rcl_wait_set_t *) override {}

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

std::shared_ptr<void>
take_data() override
{
return nullptr;
}
void
execute(std::shared_ptr<void> & data) override
execute(const std::shared_ptr<void> & data) override
{
(void) data;
}
Expand Down
4 changes: 2 additions & 2 deletions rclcpp/test/rclcpp/node_interfaces/test_node_waitables.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,15 +29,15 @@ class TestWaitable : public rclcpp::Waitable
{
public:
void add_to_wait_set(rcl_wait_set_t *) override {}
bool is_ready(rcl_wait_set_t *) override {return false;}
bool is_ready(const rcl_wait_set_t *) override {return false;}

std::shared_ptr<void>
take_data() override
{
return nullptr;
}

void execute(std::shared_ptr<void> & data) override
void execute(const std::shared_ptr<void> & data) override
{
(void) data;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ class TestWaitable : public rclcpp::Waitable
}
}

bool is_ready(rcl_wait_set_t *) override
bool is_ready(const rcl_wait_set_t *) override
{
return test_waitable_result;
}
Expand All @@ -57,7 +57,7 @@ class TestWaitable : public rclcpp::Waitable
return nullptr;
}

void execute(std::shared_ptr<void> & data) override
void execute(const std::shared_ptr<void> & data) override
{
(void) data;
}
Expand Down
4 changes: 2 additions & 2 deletions rclcpp/test/rclcpp/test_memory_strategy.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,9 +36,9 @@ class TestWaitable : public rclcpp::Waitable
{
public:
void add_to_wait_set(rcl_wait_set_t *) override {}
bool is_ready(rcl_wait_set_t *) override {return true;}
bool is_ready(const rcl_wait_set_t *) override {return true;}
std::shared_ptr<void> take_data() override {return nullptr;}
void execute(std::shared_ptr<void> & data) override {(void)data;}
void execute(const std::shared_ptr<void> & data) override {(void)data;}
};

class TestMemoryStrategy : public ::testing::Test
Expand Down
4 changes: 2 additions & 2 deletions rclcpp/test/rclcpp/wait_set_policies/test_dynamic_storage.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,12 +53,12 @@ class TestWaitable : public rclcpp::Waitable

void add_to_wait_set(rcl_wait_set_t *) override {}

bool is_ready(rcl_wait_set_t *) override {return is_ready_;}
bool is_ready(const rcl_wait_set_t *) override {return is_ready_;}

std::shared_ptr<void> take_data() override {return nullptr;}

void
execute(std::shared_ptr<void> & data) override {(void)data;}
execute(const std::shared_ptr<void> & data) override {(void)data;}

void set_is_ready(bool value) {is_ready_ = value;}

Expand Down
4 changes: 2 additions & 2 deletions rclcpp/test/rclcpp/wait_set_policies/test_static_storage.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,12 +53,12 @@ class TestWaitable : public rclcpp::Waitable

void add_to_wait_set(rcl_wait_set_t *) override {}

bool is_ready(rcl_wait_set_t *) override {return is_ready_;}
bool is_ready(const rcl_wait_set_t *) override {return is_ready_;}

std::shared_ptr<void> take_data() override {return nullptr;}

void
execute(std::shared_ptr<void> & data) override {(void)data;}
execute(const std::shared_ptr<void> & data) override {(void)data;}

void set_is_ready(bool value) {is_ready_ = value;}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -58,12 +58,12 @@ class TestWaitable : public rclcpp::Waitable
}
}

bool is_ready(rcl_wait_set_t *) override {return is_ready_;}
bool is_ready(const rcl_wait_set_t *) override {return is_ready_;}

std::shared_ptr<void> take_data() override {return nullptr;}

void
execute(std::shared_ptr<void> & data) override {(void)data;}
execute(const std::shared_ptr<void> & data) override {(void)data;}

void set_is_ready(bool value) {is_ready_ = value;}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -53,12 +53,12 @@ class TestWaitable : public rclcpp::Waitable

void add_to_wait_set(rcl_wait_set_t *) override {}

bool is_ready(rcl_wait_set_t *) override {return is_ready_;}
bool is_ready(const rcl_wait_set_t *) override {return is_ready_;}

std::shared_ptr<void> take_data() override {return nullptr;}

void
execute(std::shared_ptr<void> & data) override {(void)data;}
execute(const std::shared_ptr<void> & data) override {(void)data;}

void set_is_ready(bool value) {is_ready_ = value;}

Expand Down
46 changes: 46 additions & 0 deletions rclcpp/test/rclcpp/waitables/test_intra_process_waitable.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,46 @@
// Copyright 2024 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include <gtest/gtest.h>

#include "rclcpp/rclcpp.hpp"
#include "test_msgs/msg/empty.hpp"

#include "./waitable_test_helpers.hpp"

class TestIntraProcessWaitable : public ::testing::Test
{
protected:
static void SetUpTestCase() { rclcpp::init(0, nullptr); }
static void TearDownTestCase() { rclcpp::shutdown(); }
};

TEST_F(TestIntraProcessWaitable, test_that_waitable_stays_ready_after_second_wait) {
auto node = std::make_shared<rclcpp::Node>(
"test_node",
rclcpp::NodeOptions().use_intra_process_comms(true));

using test_msgs::msg::Empty;
auto sub = node->create_subscription<Empty>("test_topic", 10, [](const Empty &) {});
auto pub = node->create_publisher<Empty>("test_topic", 10);

auto make_sub_intra_process_waitable_ready = [pub]() {
pub->publish(Empty());
};

rclcpp::test::waitables::do_test_that_waitable_stays_ready_after_second_wait(
sub->get_intra_process_waitable(),
make_sub_intra_process_waitable_ready,
true /* expected_to_stay_ready */);
}
Loading

0 comments on commit bf03d2f

Please sign in to comment.