15 #ifndef CONCEALER__AUTOWARE_USER_HPP_
16 #define CONCEALER__AUTOWARE_USER_HPP_
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>
34 #include <geometry_msgs/msg/accel.hpp>
35 #include <geometry_msgs/msg/pose_stamped.hpp>
37 #include <rclcpp/rclcpp.hpp>
38 #include <traffic_simulator_msgs/msg/waypoints_array.hpp>
61 std::atomic<bool> is_stop_requested =
false;
63 bool is_autoware_exited =
false;
65 auto checkAutowareProcess() -> void;
89 template <typename... Ts>
116 virtual auto
initialize(const geometry_msgs::msg::Pose &) ->
void = 0;
128 virtual auto
plan(const
std::vector<geometry_msgs::msg::PoseStamped> &) ->
void = 0;
140 virtual auto
getWaypoints() const -> traffic_simulator_msgs::msg::WaypointsArray = 0;
152 virtual auto
rethrow() const noexcept(false) ->
void;
162 auto operator<<(std::ostream &,
const TurnIndicatorsCommand &) -> std::ostream &;
164 auto operator>>(std::istream &, TurnIndicatorsCommand &) -> std::istream &;
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 ¶meters)
Definition: launch.hpp:37
Definition: junit5.hpp:25
std::string string
Definition: junit5.hpp:26