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 #include <sys/wait.h>
19 
20 #if __has_include(<autoware_adapi_v1_msgs/msg/localization_initialization_state.hpp>)
21 #include <autoware_adapi_v1_msgs/msg/localization_initialization_state.hpp>
22 #endif
23 
24 #include <autoware_adapi_v1_msgs/msg/mrm_state.hpp>
25 #include <autoware_adapi_v1_msgs/srv/change_operation_mode.hpp>
26 #include <autoware_adapi_v1_msgs/srv/clear_route.hpp>
27 #include <autoware_adapi_v1_msgs/srv/initialize_localization.hpp>
28 #include <autoware_adapi_v1_msgs/srv/set_route_points.hpp>
29 #include <autoware_control_msgs/msg/control.hpp>
30 #include <autoware_system_msgs/msg/autoware_state.hpp>
31 #include <autoware_vehicle_msgs/msg/gear_command.hpp>
32 #include <autoware_vehicle_msgs/msg/turn_indicators_command.hpp>
35 #include <concealer/publisher.hpp>
36 #include <concealer/service.hpp>
37 #include <concealer/subscriber.hpp>
38 #include <concealer/task_queue.hpp>
40 #include <concealer/visibility.hpp>
41 #include <geometry_msgs/msg/accel.hpp>
42 #include <geometry_msgs/msg/pose_stamped.hpp>
43 #include <geometry_msgs/msg/pose_with_covariance_stamped.hpp>
44 #include <rclcpp/rclcpp.hpp>
45 #include <tier4_external_api_msgs/msg/emergency.hpp>
46 #include <tier4_external_api_msgs/srv/engage.hpp>
47 #include <tier4_external_api_msgs/srv/set_velocity_limit.hpp>
48 #include <tier4_planning_msgs/msg/trajectory.hpp>
49 #include <tier4_rtc_msgs/msg/cooperate_status_array.hpp>
50 #include <tier4_rtc_msgs/srv/auto_mode_with_module.hpp>
51 #include <tier4_rtc_msgs/srv/cooperate_commands.hpp>
52 #include <traffic_simulator_msgs/msg/waypoints_array.hpp>
53 #include <utility>
54 
55 namespace concealer
56 {
57 struct FieldOperatorApplication : public rclcpp::Node,
58  public TransitionAssertion<FieldOperatorApplication>
59 {
60  std::atomic<bool> is_stop_requested = false;
61 
62  bool is_autoware_exited = false;
63 
64  const pid_t process_id = 0;
65 
66  bool initialized = false;
67 
68  std::string autoware_state = "LAUNCHING";
69 
71 
73 
74  // clang-format off
75  using AutowareState = autoware_system_msgs::msg::AutowareState;
76  using Control = autoware_control_msgs::msg::Control;
77  using CooperateStatusArray = tier4_rtc_msgs::msg::CooperateStatusArray;
78  using Emergency = tier4_external_api_msgs::msg::Emergency;
79  using LocalizationInitializationState = autoware_adapi_v1_msgs::msg::LocalizationInitializationState;
80  using MrmState = autoware_adapi_v1_msgs::msg::MrmState;
81  using Trajectory = tier4_planning_msgs::msg::Trajectory;
82  using TurnIndicatorsCommand = autoware_vehicle_msgs::msg::TurnIndicatorsCommand;
83 
84  using ClearRoute = autoware_adapi_v1_msgs::srv::ClearRoute;
85  using CooperateCommands = tier4_rtc_msgs::srv::CooperateCommands;
86  using Engage = tier4_external_api_msgs::srv::Engage;
87  using InitializeLocalization = autoware_adapi_v1_msgs::srv::InitializeLocalization;
88  using SetRoutePoints = autoware_adapi_v1_msgs::srv::SetRoutePoints;
89  using AutoModeWithModule = tier4_rtc_msgs::srv::AutoModeWithModule;
90  using SetVelocityLimit = tier4_external_api_msgs::srv::SetVelocityLimit;
91  using ChangeOperationMode = autoware_adapi_v1_msgs::srv::ChangeOperationMode;
92 
97 #if __has_include(<autoware_adapi_v1_msgs/msg/localization_initialization_state.hpp>)
99 #endif
104 
113  // clang-format on
114 
115  /*
116  The task queue must be deconstructed before any services, so it must be
117  the last class data member. (Class data members are constructed in
118  declaration order and deconstructed in reverse order.)
119  */
121 
122  CONCEALER_PUBLIC explicit FieldOperatorApplication(const pid_t);
123 
125 
126  auto spinSome() -> void;
127 
128  auto engage() -> void;
129 
130  auto engageable() const -> bool;
131 
132  auto engaged() const -> bool;
133 
134  auto initialize(const geometry_msgs::msg::Pose &) -> void;
135 
136  auto plan(const std::vector<geometry_msgs::msg::PoseStamped> &) -> void;
137 
138  auto clearRoute() -> void;
139 
140  auto getWaypoints() const -> traffic_simulator_msgs::msg::WaypointsArray;
141 
142  auto requestAutoModeForCooperation(const std::string &, bool) -> void;
143 
144  auto rethrow() const { task_queue.rethrow(); }
145 
146  auto sendCooperateCommand(const std::string &, const std::string &) -> void;
147 
148  auto setVelocityLimit(double) -> void;
149 
150  auto enableAutowareControl() -> void;
151 };
152 } // namespace concealer
153 
154 #endif // CONCEALER__AUTOWARE_USER_HPP_
Definition: task_queue.hpp:28
void rethrow() const
Definition: task_queue.cpp:55
#define CONCEALER_PUBLIC
Definition: visibility.hpp:49
Definition: autoware_universe.hpp:40
Definition: lanelet_wrapper.hpp:39
geometry_msgs::msg::Pose Pose
Definition: lanelet_wrapper.hpp:65
geometry_msgs::msg::PoseStamped PoseStamped
Definition: lanelet_wrapper.hpp:66
std::string string
Definition: junit5.hpp:26
Definition: field_operator_application.hpp:59
Subscriber< Trajectory > getTrajectory
Definition: field_operator_application.hpp:102
Subscriber< AutowareState > getAutowareState
Definition: field_operator_application.hpp:93
auto getWaypoints() const -> traffic_simulator_msgs::msg::WaypointsArray
Definition: field_operator_application.cpp:310
tier4_rtc_msgs::srv::AutoModeWithModule AutoModeWithModule
Definition: field_operator_application.hpp:89
autoware_vehicle_msgs::msg::TurnIndicatorsCommand TurnIndicatorsCommand
Definition: field_operator_application.hpp:82
Service< SetRoutePoints > requestSetRoutePoints
Definition: field_operator_application.hpp:109
Subscriber< Emergency > getEmergencyState
Definition: field_operator_application.hpp:96
auto requestAutoModeForCooperation(const std::string &, bool) -> void
Definition: field_operator_application.cpp:393
Service< Engage > requestEngage
Definition: field_operator_application.hpp:107
autoware_control_msgs::msg::Control Control
Definition: field_operator_application.hpp:76
autoware_adapi_v1_msgs::srv::InitializeLocalization InitializeLocalization
Definition: field_operator_application.hpp:87
autoware_adapi_v1_msgs::srv::ClearRoute ClearRoute
Definition: field_operator_application.hpp:84
bool initialized
Definition: field_operator_application.hpp:66
Subscriber< Control > getCommand
Definition: field_operator_application.hpp:94
auto initialize(const geometry_msgs::msg::Pose &) -> void
Definition: field_operator_application.cpp:321
auto engaged() const -> bool
Definition: field_operator_application.cpp:304
Subscriber< CooperateStatusArray > getCooperateStatusArray
Definition: field_operator_application.hpp:95
Service< SetVelocityLimit > requestSetVelocityLimit
Definition: field_operator_application.hpp:111
tier4_rtc_msgs::msg::CooperateStatusArray CooperateStatusArray
Definition: field_operator_application.hpp:77
Subscriber< priority::PathWithLaneId > getPathWithLaneId
Definition: field_operator_application.hpp:101
auto enableAutowareControl() -> void
Definition: field_operator_application.cpp:275
auto setVelocityLimit(double) -> void
Definition: field_operator_application.cpp:508
std::string minimum_risk_maneuver_state
Definition: field_operator_application.hpp:70
bool is_autoware_exited
Definition: field_operator_application.hpp:62
TaskQueue task_queue
Definition: field_operator_application.hpp:120
tier4_external_api_msgs::srv::SetVelocityLimit SetVelocityLimit
Definition: field_operator_application.hpp:90
Service< ChangeOperationMode > requestEnableAutowareControl
Definition: field_operator_application.hpp:112
auto clearRoute() -> void
Definition: field_operator_application.cpp:263
autoware_adapi_v1_msgs::msg::MrmState MrmState
Definition: field_operator_application.hpp:80
tier4_external_api_msgs::msg::Emergency Emergency
Definition: field_operator_application.hpp:78
auto sendCooperateCommand(const std::string &, const std::string &) -> void
Definition: field_operator_application.cpp:418
auto engageable() const -> bool
Definition: field_operator_application.cpp:298
~FieldOperatorApplication()
Definition: field_operator_application.cpp:185
Service< InitializeLocalization > requestInitialPose
Definition: field_operator_application.hpp:108
Subscriber< MrmState > getMrmState
Definition: field_operator_application.hpp:100
Service< ClearRoute > requestClearRoute
Definition: field_operator_application.hpp:105
auto plan(const std::vector< geometry_msgs::msg::PoseStamped > &) -> void
Definition: field_operator_application.cpp:349
const pid_t process_id
Definition: field_operator_application.hpp:64
std::string autoware_state
Definition: field_operator_application.hpp:68
tier4_planning_msgs::msg::Trajectory Trajectory
Definition: field_operator_application.hpp:81
tier4_rtc_msgs::srv::CooperateCommands CooperateCommands
Definition: field_operator_application.hpp:85
autoware_adapi_v1_msgs::srv::SetRoutePoints SetRoutePoints
Definition: field_operator_application.hpp:88
Subscriber< TurnIndicatorsCommand > getTurnIndicatorsCommand
Definition: field_operator_application.hpp:103
auto engage() -> void
Definition: field_operator_application.cpp:283
Service< AutoModeWithModule > requestSetRtcAutoMode
Definition: field_operator_application.hpp:110
auto rethrow() const
Definition: field_operator_application.hpp:144
auto spinSome() -> void
Definition: field_operator_application.cpp:521
Service< CooperateCommands > requestCooperateCommands
Definition: field_operator_application.hpp:106
autoware_adapi_v1_msgs::srv::ChangeOperationMode ChangeOperationMode
Definition: field_operator_application.hpp:91
CONCEALER_PUBLIC FieldOperatorApplication(const pid_t)
Definition: field_operator_application.cpp:80
tier4_external_api_msgs::srv::Engage Engage
Definition: field_operator_application.hpp:86
std::string minimum_risk_maneuver_behavior
Definition: field_operator_application.hpp:72
autoware_adapi_v1_msgs::msg::LocalizationInitializationState LocalizationInitializationState
Definition: field_operator_application.hpp:79
std::atomic< bool > is_stop_requested
Definition: field_operator_application.hpp:60
autoware_system_msgs::msg::AutowareState AutowareState
Definition: field_operator_application.hpp:75
Definition: transition_assertion.hpp:27