scenario_simulator_v2 C++ API
transition_assertion.hpp
Go to the documentation of this file.
1 // Copyright 2015 TIER IV, Inc. All rights reserved.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef CONCEALER__TRANSITION_ASSERTION_HPP_
16 #define CONCEALER__TRANSITION_ASSERTION_HPP_
17 
18 #include <chrono>
19 #include <rclcpp/node.hpp>
20 #include <rclcpp/rate.hpp>
22 
23 namespace concealer
24 {
25 template <typename Autoware>
27 {
28 protected:
29  const std::chrono::steady_clock::time_point start;
30 
31  const std::chrono::seconds initialize_duration;
32 
34 
36  : start(std::chrono::steady_clock::now()), initialize_duration([]() {
37  auto node = rclcpp::Node("get_parameter", "simulation");
38  node.declare_parameter("initialize_duration", 0);
39  return node.get_parameter("initialize_duration").as_int();
40  }())
41  {
42  }
43 
44 #define DEFINE_WAIT_FOR_AUTOWARE_STATE_TO_BE(STATE) \
45  template <typename Thunk = void (*)(), typename Interval = std::chrono::seconds> \
46  auto waitForAutowareStateToBe_##STATE( \
47  Thunk && thunk = [] {}, Interval interval = std::chrono::seconds(1)) \
48  { \
49  for (thunk(); not static_cast<const Autoware &>(*this).is_stop_requested.load() and \
50  static_cast<const Autoware &>(*this).autoware_state != #STATE; \
51  rclcpp::GenericRate<std::chrono::steady_clock>(interval).sleep()) { \
52  if ( \
53  have_never_been_engaged and \
54  start + initialize_duration <= std::chrono::steady_clock::now()) { \
55  const auto state = static_cast<const Autoware &>(*this).autoware_state; \
56  throw common::AutowareError( \
57  "Simulator waited for the Autoware state to transition to " #STATE \
58  ", but time is up. The current Autoware state is ", \
59  (state.empty() ? "not published yet" : state)); \
60  } else { \
61  thunk(); \
62  } \
63  } \
64  if constexpr (std::string_view(#STATE) == std::string_view("DRIVING")) { \
65  have_never_been_engaged = false; \
66  } \
67  } \
68  static_assert(true)
69 
77 
78 #undef DEFINE_WAIT_FOR_AUTOWARE_STATE_TO_BE
79 };
80 } // namespace concealer
81 
82 #endif // CONCEALER__TRANSITION_ASSERTION_HPP_
Definition: autoware_universe.hpp:40
Definition: cache.hpp:27
Definition: transition_assertion.hpp:27
DEFINE_WAIT_FOR_AUTOWARE_STATE_TO_BE(WAITING_FOR_ENGAGE)
DEFINE_WAIT_FOR_AUTOWARE_STATE_TO_BE(INITIALIZING)
DEFINE_WAIT_FOR_AUTOWARE_STATE_TO_BE(ARRIVED_GOAL)
DEFINE_WAIT_FOR_AUTOWARE_STATE_TO_BE(FINALIZING)
TransitionAssertion()
Definition: transition_assertion.hpp:35
DEFINE_WAIT_FOR_AUTOWARE_STATE_TO_BE(PLANNING)
bool have_never_been_engaged
Definition: transition_assertion.hpp:33
const std::chrono::seconds initialize_duration
Definition: transition_assertion.hpp:31
const std::chrono::steady_clock::time_point start
Definition: transition_assertion.hpp:29
DEFINE_WAIT_FOR_AUTOWARE_STATE_TO_BE(WAITING_FOR_ROUTE)