20 #include <condition_variable>
25 #include <gmock/gmock.h>
27 #include <rclcpp/logging.hpp>
31 const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"moveit.pilz_industrial_motion_planner.async_test");
88 bool barricade(
const std::string& clear_event,
const int timeout_ms = -1);
98 bool barricade(std::initializer_list<std::string> clear_events,
const int timeout_ms = -1);
102 std::condition_variable
cv_;
108 #define BARRIER(...) EXPECT_TRUE(barricade(__VA_ARGS__))
109 #define BARRIER_FATAL(...) ASSERT_TRUE(barricade(__VA_ARGS__))
111 #define ACTION_OPEN_BARRIER(str) \
112 ::testing::InvokeWithoutArgs([this](void) { \
113 this->triggerClearEvent(str); \
116 #define ACTION_OPEN_BARRIER_VOID(str) ::testing::InvokeWithoutArgs([this]() { this->triggerClearEvent(str); })
120 std::lock_guard<std::mutex> lk(
m_);
124 RCLCPP_DEBUG(
LOGGER,
"Clearing Barricade[%s]", event.c_str());
129 RCLCPP_WARN(
LOGGER,
"Triggered event " << event <<
" despite not waiting for it.");
136 return barricade({ clear_event }, timeout_ms);
141 std::unique_lock<std::mutex> lk(
m_);
143 std::stringstream events_stringstream;
144 for (
const auto& event : clear_events)
146 events_stringstream <<
event <<
", ";
148 RCLCPP_DEBUG(
LOGGER,
"Adding Barricade[%s]", events_stringstream.str().c_str());
151 [
this](
const std::string& event) { return this->waitlist_.count(event) == 0; });
154 auto end_time_point = std::chrono::system_clock::now() + std::chrono::milliseconds(timeout_ms);
164 std::cv_status status =
cv_.wait_for(lk, end_time_point - std::chrono::system_clock::now());
165 if (status == std::cv_status::timeout)
Test class that allows the handling of asynchronous test objects.
void triggerClearEvent(const std::string &event)
Triggers a clear event. If a call to barricade is currently pending it will unblock as soon as all cl...
bool barricade(const std::string &clear_event, const int timeout_ms=-1)
Will block until the event given by clear_event is triggered or a timeout is reached....
std::set< std::string > waitlist_
std::condition_variable cv_
std::set< std::string > clear_events_
const rclcpp::Logger LOGGER