scenario_simulator_v2 C++ API
Classes | Namespaces | Macros | Functions
transition_assertion.hpp File Reference
#include <autoware_auto_system_msgs/msg/autoware_state.hpp>
#include <chrono>
#include <rclcpp/node.hpp>
#include <rclcpp/rate.hpp>
#include <scenario_simulator_exception/exception.hpp>
Include dependency graph for transition_assertion.hpp:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  concealer::TransitionAssertion< Autoware >
 

Namespaces

 concealer
 

Macros

#define DEFINE_WAIT_FOR_AUTOWARE_STATE_TO_BE_WITH_INITIALIZE_TIME_LIMIT(STATE)
 
#define DEFINE_WAIT_FOR_AUTOWARE_STATE_TO_BE(STATE)
 

Functions

template<typename T >
auto concealer::getParameter (const std::string &name, T value={})
 

Macro Definition Documentation

◆ DEFINE_WAIT_FOR_AUTOWARE_STATE_TO_BE

#define DEFINE_WAIT_FOR_AUTOWARE_STATE_TO_BE (   STATE)
Value:
template <typename Thunk = void (*)()> \
void waitForAutowareStateToBe##STATE( \
Thunk && thunk = [] {}, std::chrono::seconds interval = std::chrono::seconds(1)) \
{ \
using std::chrono::duration_cast; \
using std::chrono::seconds; \
rate_type rate(interval); \
for (thunk(); not asAutoware().isStopRequested() and not asAutoware().is##STATE(); \
rate.sleep()) { \
auto now = clock_type::now(); \
RCLCPP_INFO_STREAM( \
asAutoware().get_logger(), \
"Simulator waiting for Autoware state to be " #STATE " (remain: " \
<< duration_cast<seconds>(start + initialize_duration - now).count() << ")."); \
thunk(); \
} \
RCLCPP_INFO_STREAM( \
asAutoware().get_logger(), \
"Autoware is " << asAutoware().getAutowareStateName() << " now."); \
} \
static_assert(true, "")
#define STATE(IDENTIFIER)
auto start(Ts &&... xs) -> pid_t
Definition: record.hpp:40

◆ DEFINE_WAIT_FOR_AUTOWARE_STATE_TO_BE_WITH_INITIALIZE_TIME_LIMIT

#define DEFINE_WAIT_FOR_AUTOWARE_STATE_TO_BE_WITH_INITIALIZE_TIME_LIMIT (   STATE)
Value:
template <typename Thunk = void (*)()> \
void waitForAutowareStateToBe##STATE( \
Thunk && thunk = [] {}, std::chrono::seconds interval = std::chrono::seconds(1)) \
{ \
using std::chrono::duration_cast; \
using std::chrono::seconds; \
rate_type rate(interval); \
for (thunk(); not asAutoware().isStopRequested() and not asAutoware().is##STATE(); \
rate.sleep()) { \
auto now = clock_type::now(); \
if (start + initialize_duration <= now) { \
throw makeTransitionError(#STATE); \
} else { \
RCLCPP_INFO_STREAM( \
asAutoware().get_logger(), \
"Simulator waiting for Autoware state to be " #STATE " (remain: " \
<< duration_cast<seconds>(start + initialize_duration - now).count() << ")."); \
thunk(); \
} \
} \
RCLCPP_INFO_STREAM( \
asAutoware().get_logger(), \
"Autoware is " << asAutoware().getAutowareStateName() << " now."); \
} \
static_assert(true, "")