15 #ifndef CONCEALER__AUTOWARE_USER_HPP_
16 #define CONCEALER__AUTOWARE_USER_HPP_
20 #if __has_include(<autoware_adapi_v1_msgs/msg/localization_initialization_state.hpp>)
21 #include <autoware_adapi_v1_msgs/msg/localization_initialization_state.hpp>
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>
40 #include <geometry_msgs/msg/accel.hpp>
41 #include <geometry_msgs/msg/pose_stamped.hpp>
42 #include <geometry_msgs/msg/pose_with_covariance_stamped.hpp>
43 #include <rclcpp/rclcpp.hpp>
44 #include <tier4_external_api_msgs/msg/emergency.hpp>
45 #include <tier4_external_api_msgs/srv/engage.hpp>
46 #include <tier4_external_api_msgs/srv/set_velocity_limit.hpp>
47 #include <tier4_planning_msgs/msg/path_with_lane_id.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>
76 using Control = autoware_control_msgs::msg::Control;
78 using Emergency = tier4_external_api_msgs::msg::Emergency;
80 using MrmState = autoware_adapi_v1_msgs::msg::MrmState;
85 using ClearRoute = autoware_adapi_v1_msgs::srv::ClearRoute;
87 using Engage = tier4_external_api_msgs::srv::Engage;
98 #if __has_include(<autoware_adapi_v1_msgs/msg/localization_initialization_state.hpp>)
135 auto
initialize(const geometry_msgs::msg::Pose &) ->
void;
137 auto
plan(const
std::vector<geometry_msgs::msg::PoseStamped> &) ->
void;
141 auto
getWaypoints() const -> traffic_simulator_msgs::msg::WaypointsArray;
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
std::string string
Definition: junit5.hpp:26
Definition: field_operator_application.hpp:59
Subscriber< Trajectory > getTrajectory
Definition: field_operator_application.hpp:103
Subscriber< AutowareState > getAutowareState
Definition: field_operator_application.hpp:94
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:90
autoware_vehicle_msgs::msg::TurnIndicatorsCommand TurnIndicatorsCommand
Definition: field_operator_application.hpp:83
Service< SetRoutePoints > requestSetRoutePoints
Definition: field_operator_application.hpp:110
Subscriber< Emergency > getEmergencyState
Definition: field_operator_application.hpp:97
auto requestAutoModeForCooperation(const std::string &, bool) -> void
Definition: field_operator_application.cpp:393
Service< Engage > requestEngage
Definition: field_operator_application.hpp:108
autoware_control_msgs::msg::Control Control
Definition: field_operator_application.hpp:76
autoware_adapi_v1_msgs::srv::InitializeLocalization InitializeLocalization
Definition: field_operator_application.hpp:88
autoware_adapi_v1_msgs::srv::ClearRoute ClearRoute
Definition: field_operator_application.hpp:85
bool initialized
Definition: field_operator_application.hpp:66
Subscriber< Control > getCommand
Definition: field_operator_application.hpp:95
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:96
Service< SetVelocityLimit > requestSetVelocityLimit
Definition: field_operator_application.hpp:112
tier4_rtc_msgs::msg::CooperateStatusArray CooperateStatusArray
Definition: field_operator_application.hpp:77
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:121
tier4_external_api_msgs::srv::SetVelocityLimit SetVelocityLimit
Definition: field_operator_application.hpp:91
Service< ChangeOperationMode > requestEnableAutowareControl
Definition: field_operator_application.hpp:113
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:109
Subscriber< MrmState > getMrmState
Definition: field_operator_application.hpp:101
Service< ClearRoute > requestClearRoute
Definition: field_operator_application.hpp:106
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
Subscriber< PathWithLaneId > getPathWithLaneId
Definition: field_operator_application.hpp:102
std::string autoware_state
Definition: field_operator_application.hpp:68
tier4_planning_msgs::msg::Trajectory Trajectory
Definition: field_operator_application.hpp:82
tier4_rtc_msgs::srv::CooperateCommands CooperateCommands
Definition: field_operator_application.hpp:86
autoware_adapi_v1_msgs::srv::SetRoutePoints SetRoutePoints
Definition: field_operator_application.hpp:89
Subscriber< TurnIndicatorsCommand > getTurnIndicatorsCommand
Definition: field_operator_application.hpp:104
auto engage() -> void
Definition: field_operator_application.cpp:283
Service< AutoModeWithModule > requestSetRtcAutoMode
Definition: field_operator_application.hpp:111
auto rethrow() const
Definition: field_operator_application.hpp:145
auto spinSome() -> void
Definition: field_operator_application.cpp:521
Service< CooperateCommands > requestCooperateCommands
Definition: field_operator_application.hpp:107
autoware_adapi_v1_msgs::srv::ChangeOperationMode ChangeOperationMode
Definition: field_operator_application.hpp:92
CONCEALER_PUBLIC FieldOperatorApplication(const pid_t)
Definition: field_operator_application.cpp:80
tier4_planning_msgs::msg::PathWithLaneId PathWithLaneId
Definition: field_operator_application.hpp:81
tier4_external_api_msgs::srv::Engage Engage
Definition: field_operator_application.hpp:87
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