scenario_simulator_v2 C++ API
field_operator_application.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__AUTOWARE_USER_HPP_
16 #define CONCEALER__AUTOWARE_USER_HPP_
17 
18 // #define CONCEALER_ISOLATE_STANDARD_OUTPUT
19 
20 #include <sys/wait.h>
21 
22 #include <autoware_adapi_v1_msgs/msg/mrm_state.hpp>
23 #include <autoware_auto_control_msgs/msg/ackermann_control_command.hpp>
24 #include <autoware_auto_planning_msgs/msg/path_with_lane_id.hpp>
25 #include <autoware_auto_system_msgs/msg/emergency_state.hpp>
26 #include <autoware_auto_vehicle_msgs/msg/turn_indicators_command.hpp>
27 #include <chrono>
29 #include <concealer/launch.hpp>
30 #include <concealer/task_queue.hpp>
32 #include <concealer/visibility.hpp>
33 #include <exception>
34 #include <geometry_msgs/msg/accel.hpp>
35 #include <geometry_msgs/msg/pose_stamped.hpp>
36 #include <limits>
37 #include <rclcpp/rclcpp.hpp>
38 #include <traffic_simulator_msgs/msg/waypoints_array.hpp>
39 #include <utility>
40 
41 namespace concealer
42 {
43 template <typename T>
45 
46 /* ---- NOTE -------------------------------------------------------------------
47  *
48  * The magic class 'FieldOperatorApplication' is a class that makes it easy to work with
49  * Autoware from C++. The main features of this class are as follows
50  *
51  * (1) Launch Autoware in an independent process upon instantiation of the
52  * class.
53  * (2) Properly terminates the Autoware process started by the constructor
54  * upon destruction of the class.
55  * (3) Probably the simplest instructions to Autoware, consisting of
56  * initialize, plan, and engage.
57  *
58  * -------------------------------------------------------------------------- */
59 class FieldOperatorApplication : public rclcpp::Node
60 {
61  std::atomic<bool> is_stop_requested = false;
62 
63  bool is_autoware_exited = false;
64 
65  auto checkAutowareProcess() -> void;
66 
67 protected:
68  const pid_t process_id = 0;
69 
71 
72  bool initialize_was_called = false;
73 
74  auto stopRequest() noexcept -> void;
75 
76  auto isStopRequested() const noexcept -> bool;
77 
78  // this method is purely virtual because different Autoware types are killed differently
79  // currently, we are not sure why this is the case so detailed investigation is needed
80  virtual auto sendSIGINT() -> void = 0;
81 
82  // method called in destructor of a derived class
83  // because it is difficult to differentiate shutting down behavior in destructor of a base class
84  auto shutdownAutoware() -> void;
85 
86 public:
87  CONCEALER_PUBLIC explicit FieldOperatorApplication(const pid_t = 0);
88 
89  template <typename... Ts>
91  : FieldOperatorApplication(ros2_launch(std::forward<decltype(xs)>(xs)...))
92  {
93  }
94 
95  ~FieldOperatorApplication() override = default;
96 
97  auto spinSome() -> void;
98 
99  /* ---- NOTE -------------------------------------------------------------------
100  *
101  * Send an engagement request to Autoware. If Autoware does not have an
102  * engagement equivalent, this operation can be nop (No operation).
103  *
104  * -------------------------------------------------------------------------- */
105  virtual auto engage() -> void = 0;
106 
107  virtual auto engageable() const -> bool = 0;
108 
109  virtual auto engaged() const -> bool = 0;
110 
111  /* ---- NOTE -------------------------------------------------------------------
112  *
113  * Send initial_pose to Autoware.
114  *
115  * -------------------------------------------------------------------------- */
116  virtual auto initialize(const geometry_msgs::msg::Pose &) -> void = 0;
117 
118  /* ---- NOTE -------------------------------------------------------------------
119  *
120  * Send the destination and route constraint points to Autoware. The argument
121  * route is guaranteed to be size 1 or greater, and its last element is the
122  * destination. When the size of a route is 2 or greater, the non-last element
123  * is the route constraint. That is, Autoware must go through the element
124  * points on the given'route' starting at index 0 and stop at index
125  * route.size() - 1.
126  *
127  * -------------------------------------------------------------------------- */
128  virtual auto plan(const std::vector<geometry_msgs::msg::PoseStamped> &) -> void = 0;
129 
130  virtual auto clearRoute() -> void = 0;
131 
132  virtual auto getAutowareStateName() const -> std::string = 0;
133 
134  virtual auto getMinimumRiskManeuverBehaviorName() const -> std::string = 0;
135 
136  virtual auto getMinimumRiskManeuverStateName() const -> std::string = 0;
137 
138  virtual auto getEmergencyStateName() const -> std::string = 0;
139 
140  virtual auto getWaypoints() const -> traffic_simulator_msgs::msg::WaypointsArray = 0;
141 
142  /* */ auto initialized() const noexcept { return initialize_was_called; }
143 
144  virtual auto requestAutoModeForCooperation(const std::string &, bool) -> void = 0;
145 
146  // different autowares accept different initial target speed
147  virtual auto restrictTargetSpeed(double) const -> double = 0;
148 
149  virtual auto getTurnIndicatorsCommand() const
150  -> autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand;
151 
152  virtual auto rethrow() const noexcept(false) -> void;
153 
154  virtual auto sendCooperateCommand(const std::string &, const std::string &) -> void = 0;
155 
156  virtual auto setVelocityLimit(double) -> void = 0;
157 };
158 } // namespace concealer
159 
161 {
162 auto operator<<(std::ostream &, const TurnIndicatorsCommand &) -> std::ostream &;
163 
164 auto operator>>(std::istream &, TurnIndicatorsCommand &) -> std::istream &;
165 } // namespace autoware_auto_vehicle_msgs::msg
166 
167 #endif // CONCEALER__AUTOWARE_USER_HPP_
Definition: field_operator_application.hpp:44
Definition: field_operator_application.hpp:60
virtual auto requestAutoModeForCooperation(const std::string &, bool) -> void=0
virtual auto getTurnIndicatorsCommand() const -> autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand
Definition: field_operator_application.cpp:149
auto shutdownAutoware() -> void
Definition: field_operator_application.cpp:72
auto stopRequest() noexcept -> void
Definition: field_operator_application.cpp:29
virtual auto getWaypoints() const -> traffic_simulator_msgs::msg::WaypointsArray=0
virtual auto getMinimumRiskManeuverStateName() const -> std::string=0
TaskQueue task_queue
Definition: field_operator_application.hpp:70
virtual auto restrictTargetSpeed(double) const -> double=0
virtual auto engage() -> void=0
virtual auto sendCooperateCommand(const std::string &, const std::string &) -> void=0
auto isStopRequested() const noexcept -> bool
Definition: field_operator_application.cpp:31
virtual auto getMinimumRiskManeuverBehaviorName() const -> std::string=0
virtual auto plan(const std::vector< geometry_msgs::msg::PoseStamped > &) -> void=0
~FieldOperatorApplication() override=default
const pid_t process_id
Definition: field_operator_application.hpp:68
virtual auto sendSIGINT() -> void=0
virtual auto getAutowareStateName() const -> std::string=0
virtual auto clearRoute() -> void=0
virtual auto getEmergencyStateName() const -> std::string=0
auto initialized() const noexcept
Definition: field_operator_application.hpp:142
auto spinSome() -> void
Definition: field_operator_application.cpp:36
virtual auto setVelocityLimit(double) -> void=0
virtual auto rethrow() const noexcept(false) -> void
Definition: field_operator_application.cpp:162
bool initialize_was_called
Definition: field_operator_application.hpp:72
virtual auto engageable() const -> bool=0
virtual auto engaged() const -> bool=0
virtual auto initialize(const geometry_msgs::msg::Pose &) -> void=0
Definition: task_queue.hpp:28
#define CONCEALER_PUBLIC
Definition: visibility.hpp:49
auto operator>>(std::istream &, TurnIndicatorsCommand &) -> std::istream &
Definition: field_operator_application.hpp:161
Definition: autoware.hpp:30
auto operator<<(std::ostream &ostream, const lister< N, Tuples > &lister) -> std::ostream &
Definition: field_operator_application_for_autoware_universe.cpp:39
auto ros2_launch(const std::string &package, const std::string &file, const Parameters &parameters)
Definition: launch.hpp:37
Definition: cache.hpp:27
Definition: junit5.hpp:25
std::string string
Definition: junit5.hpp:26