Program Listing for File async_test.h

Return to documentation for file (include/pilz_industrial_motion_planner_testutils/async_test.h)

/*
 * Copyright (c) 2018 Pilz GmbH & Co. KG
 *
 * 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.
 */

#pragma once

#include <mutex>
#include <condition_variable>
#include <algorithm>
#include <chrono>
#include <string>

#include <gmock/gmock.h>

#include <rclcpp/logging.hpp>

namespace testing
{
static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.pilz_industrial_motion_planner.async_test");
class AsyncTest
{
public:
  void triggerClearEvent(const std::string& event);

  bool barricade(const std::string& clear_event, const int timeout_ms = -1);

  bool barricade(std::initializer_list<std::string> clear_events, const int timeout_ms = -1);

protected:
  std::mutex m_;
  std::condition_variable cv_;
  std::set<std::string> clear_events_{};
  std::set<std::string> waitlist_{};
};

// for better readability in tests
#define BARRIER(...) EXPECT_TRUE(barricade(__VA_ARGS__))
#define BARRIER_FATAL(...) ASSERT_TRUE(barricade(__VA_ARGS__))

#define ACTION_OPEN_BARRIER(str)                                                                                       \
  ::testing::InvokeWithoutArgs([this](void) {                                                                          \
    this->triggerClearEvent(str);                                                                                      \
    return true;                                                                                                       \
  })
#define ACTION_OPEN_BARRIER_VOID(str) ::testing::InvokeWithoutArgs([this]() { this->triggerClearEvent(str); })

inline void AsyncTest::triggerClearEvent(const std::string& event)
{
  std::lock_guard<std::mutex> lk(m_);

  if (clear_events_.empty())
  {
    RCLCPP_DEBUG(LOGGER, "Clearing Barricade[%s]", event.c_str());
    waitlist_.insert(event);
  }
  else if (clear_events_.erase(event) < 1)
  {
    RCLCPP_WARN(LOGGER, "Triggered event " << event << " despite not waiting for it.");
  }
  cv_.notify_one();
}

inline bool AsyncTest::barricade(const std::string& clear_event, const int timeout_ms)
{
  return barricade({ clear_event }, timeout_ms);
}

inline bool AsyncTest::barricade(std::initializer_list<std::string> clear_events, const int timeout_ms)
{
  std::unique_lock<std::mutex> lk(m_);

  std::stringstream events_stringstream;
  for (const auto& event : clear_events)
  {
    events_stringstream << event << ", ";
  }
  RCLCPP_DEBUG(LOGGER, "Adding Barricade[%s]", events_stringstream.str().c_str());

  std::copy_if(clear_events.begin(), clear_events.end(), std::inserter(clear_events_, clear_events_.end()),
               [this](const std::string& event) { return this->waitlist_.count(event) == 0; });
  waitlist_.clear();

  auto end_time_point = std::chrono::system_clock::now() + std::chrono::milliseconds(timeout_ms);

  while (!clear_events_.empty())
  {
    if (timeout_ms < 0)
    {
      cv_.wait(lk);
    }
    else
    {
      std::cv_status status = cv_.wait_for(lk, end_time_point - std::chrono::system_clock::now());
      if (status == std::cv_status::timeout)
      {
        return clear_events_.empty();
      }
    }
  }
  return true;
}

}  // namespace testing