moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
async_test.h
Go to the documentation of this file.
1/*
2 * Copyright (c) 2018 Pilz GmbH & Co. KG
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License");
5 * you may not use this file except in compliance with the License.
6 * You may obtain a copy of the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS,
12 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 * See the License for the specific language governing permissions and
14 * limitations under the License.
15 */
16
17#pragma once
18
19#include <mutex>
20#include <condition_variable>
21#include <algorithm>
22#include <chrono>
23#include <string>
24
25#include <gmock/gmock.h>
26
27#include <rclcpp/logging.hpp>
28
29namespace testing
30{
31static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.pilz_industrial_motion_planner.async_test");
70{
71public:
78 void triggerClearEvent(const std::string& event);
79
88 bool barricade(const std::string& clear_event, const int timeout_ms = -1);
89
98 bool barricade(std::initializer_list<std::string> clear_events, const int timeout_ms = -1);
99
100protected:
101 std::mutex m_;
102 std::condition_variable cv_;
103 std::set<std::string> clear_events_{};
104 std::set<std::string> waitlist_{};
105};
106
107// for better readability in tests
108#define BARRIER(...) EXPECT_TRUE(barricade(__VA_ARGS__))
109#define BARRIER_FATAL(...) ASSERT_TRUE(barricade(__VA_ARGS__))
110
111#define ACTION_OPEN_BARRIER(str) \
112 ::testing::InvokeWithoutArgs([this](void) { \
113 this->triggerClearEvent(str); \
114 return true; \
115 })
116#define ACTION_OPEN_BARRIER_VOID(str) ::testing::InvokeWithoutArgs([this]() { this->triggerClearEvent(str); })
117
118inline void AsyncTest::triggerClearEvent(const std::string& event)
119{
120 std::lock_guard<std::mutex> lk(m_);
121
122 if (clear_events_.empty())
123 {
124 RCLCPP_DEBUG(LOGGER, "Clearing Barricade[%s]", event.c_str());
125 waitlist_.insert(event);
126 }
127 else if (clear_events_.erase(event) < 1)
128 {
129 RCLCPP_WARN(LOGGER, "Triggered event " << event << " despite not waiting for it.");
130 }
131 cv_.notify_one();
132}
133
134inline bool AsyncTest::barricade(const std::string& clear_event, const int timeout_ms)
135{
136 return barricade({ clear_event }, timeout_ms);
137}
138
139inline bool AsyncTest::barricade(std::initializer_list<std::string> clear_events, const int timeout_ms)
140{
141 std::unique_lock<std::mutex> lk(m_);
142
143 std::stringstream events_stringstream;
144 for (const auto& event : clear_events)
145 {
146 events_stringstream << event << ", ";
147 }
148 RCLCPP_DEBUG(LOGGER, "Adding Barricade[%s]", events_stringstream.str().c_str());
149
150 std::copy_if(clear_events.begin(), clear_events.end(), std::inserter(clear_events_, clear_events_.end()),
151 [this](const std::string& event) { return this->waitlist_.count(event) == 0; });
152 waitlist_.clear();
153
154 auto end_time_point = std::chrono::system_clock::now() + std::chrono::milliseconds(timeout_ms);
155
156 while (!clear_events_.empty())
157 {
158 if (timeout_ms < 0)
159 {
160 cv_.wait(lk);
161 }
162 else
163 {
164 std::cv_status status = cv_.wait_for(lk, end_time_point - std::chrono::system_clock::now());
165 if (status == std::cv_status::timeout)
166 {
167 return clear_events_.empty();
168 }
169 }
170 }
171 return true;
172}
173
174} // namespace testing
Test class that allows the handling of asynchronous test objects.
Definition async_test.h:70
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...
Definition async_test.h:118
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....
Definition async_test.h:134
std::set< std::string > waitlist_
Definition async_test.h:104
std::condition_variable cv_
Definition async_test.h:102
std::set< std::string > clear_events_
Definition async_test.h:103