15 #ifndef CONCEALER__AUTOWARE_HPP_
16 #define CONCEALER__AUTOWARE_HPP_
19 #include <autoware_auto_control_msgs/msg/ackermann_control_command.hpp>
20 #include <autoware_auto_vehicle_msgs/msg/gear_command.hpp>
21 #include <autoware_auto_vehicle_msgs/msg/turn_indicators_command.hpp>
24 #include <geometry_msgs/msg/accel.hpp>
25 #include <geometry_msgs/msg/pose.hpp>
26 #include <geometry_msgs/msg/twist_stamped.hpp>
27 #include <rclcpp/rclcpp.hpp>
64 autoware_auto_control_msgs::msg::AckermannControlCommand,
69 auto
set(const geometry_msgs::msg::Accel &) ->
void;
71 auto
set(const geometry_msgs::msg::Twist &) ->
void;
73 auto
set(const geometry_msgs::msg::Pose &) ->
void;
Definition: autoware.hpp:38
virtual auto getAcceleration() const -> double=0
virtual auto getRouteLanelets() const -> std::vector< std::int64_t >=0
auto set(const geometry_msgs::msg::Accel &) -> void
Definition: autoware.cpp:38
virtual auto rethrow() -> void
Definition: autoware.cpp:60
std::atomic< geometry_msgs::msg::Pose > current_pose
Definition: autoware.hpp:44
virtual auto getGearCommand() const -> autoware_auto_vehicle_msgs::msg::GearCommand
Definition: autoware.cpp:27
virtual auto getVehicleCommand() const -> std::tuple< autoware_auto_control_msgs::msg::AckermannControlCommand, autoware_auto_vehicle_msgs::msg::GearCommand >=0
virtual auto getVelocity() const -> double=0
std::atomic< geometry_msgs::msg::Accel > current_acceleration
Definition: autoware.hpp:40
virtual auto getGearSign() const -> double=0
CONCEALER_PUBLIC Autoware()
Definition: autoware.cpp:19
virtual auto getSteeringAngle() const -> double=0
virtual auto getTurnIndicatorsCommand() const -> autoware_auto_vehicle_msgs::msg::TurnIndicatorsCommand
Definition: autoware.cpp:47
std::atomic< geometry_msgs::msg::Twist > current_twist
Definition: autoware.hpp:42
#define CONCEALER_PUBLIC
Definition: visibility.hpp:49
Definition: field_operator_application.hpp:161
Definition: autoware.hpp:30