15 #ifndef CONCEALER__AUTOWARE_UNIVERSE_HPP_
16 #define CONCEALER__AUTOWARE_UNIVERSE_HPP_
18 #include <autoware_auto_control_msgs/msg/ackermann_control_command.hpp>
19 #include <autoware_auto_planning_msgs/msg/path_with_lane_id.hpp>
20 #include <autoware_auto_vehicle_msgs/msg/control_mode_report.hpp>
21 #include <autoware_auto_vehicle_msgs/msg/gear_report.hpp>
22 #include <autoware_auto_vehicle_msgs/msg/steering_report.hpp>
23 #include <autoware_auto_vehicle_msgs/msg/turn_indicators_report.hpp>
24 #include <autoware_auto_vehicle_msgs/msg/velocity_report.hpp>
28 #include <geometry_msgs/msg/accel_with_covariance_stamped.hpp>
29 #include <nav_msgs/msg/odometry.hpp>
54 const rclcpp::TimerBase::SharedPtr localization_update_timer;
56 const rclcpp::TimerBase::SharedPtr vehicle_state_update_timer;
58 std::thread localization_and_vehicle_state_update_thread;
60 std::atomic<bool> is_stop_requested =
false;
62 std::atomic<bool> is_thrown =
false;
64 std::exception_ptr thrown;
66 auto stopAndJoin() -> void;
73 auto rethrow() ->
void override;
85 auto getGearCommand()
const -> autoware_auto_vehicle_msgs::msg::GearCommand
override;
90 autoware_auto_control_msgs::msg::AckermannControlCommand,
91 autoware_auto_vehicle_msgs::msg::GearCommand>
override;
Definition: autoware_universe.hpp:38
auto updateLocalization() -> void
Definition: autoware_universe.cpp:82
auto getGearSign() const -> double override
Definition: autoware_universe.cpp:157
CONCEALER_PUBLIC AutowareUniverse()
Definition: autoware_universe.cpp:19
auto getVehicleCommand() const -> std::tuple< autoware_auto_control_msgs::msg::AckermannControlCommand, autoware_auto_vehicle_msgs::msg::GearCommand > override
Definition: autoware_universe.cpp:168
~AutowareUniverse()
Definition: autoware_universe.cpp:52
auto getSteeringAngle() const -> double override
Definition: autoware_universe.cpp:77
auto getGearCommand() const -> autoware_auto_vehicle_msgs::msg::GearCommand override
Definition: autoware_universe.cpp:152
auto getRouteLanelets() const -> std::vector< std::int64_t > override
Definition: autoware_universe.cpp:175
auto rethrow() -> void override
Definition: autoware_universe.cpp:54
auto getAcceleration() const -> double override
Definition: autoware_universe.cpp:67
auto updateVehicleState() -> void
Definition: autoware_universe.cpp:111
auto getVelocity() const -> double override
Definition: autoware_universe.cpp:72
Definition: autoware.hpp:38
#define CONCEALER_PUBLIC
Definition: visibility.hpp:49
Definition: autoware.hpp:30