18 #ifndef VEHICLE_INTERFACE__PLATFORM_INTERFACE_HPP_ 19 #define VEHICLE_INTERFACE__PLATFORM_INTERFACE_HPP_ 22 #include <autoware_auto_msgs/msg/raw_control_command.hpp> 23 #include <autoware_auto_msgs/msg/vehicle_control_command.hpp> 24 #include <autoware_auto_msgs/msg/vehicle_odometry.hpp> 25 #include <autoware_auto_msgs/msg/vehicle_state_command.hpp> 26 #include <autoware_auto_msgs/msg/vehicle_state_report.hpp> 27 #include <autoware_auto_msgs/srv/autonomy_mode_change.hpp> 28 #include <vehicle_interface/visibility_control.hpp> 34 using autoware_auto_msgs::msg::RawControlCommand;
36 using autoware_auto_msgs::msg::VehicleStateCommand;
37 using autoware_auto_msgs::msg::VehicleStateReport;
38 using autoware_auto_msgs::msg::VehicleOdometry;
46 namespace vehicle_interface
67 virtual bool8_t update(std::chrono::nanoseconds timeout) = 0;
73 virtual bool8_t send_state_command(
const VehicleStateCommand & msg) = 0;
85 virtual bool8_t send_control_command(
const RawControlCommand & msg) = 0;
91 virtual bool8_t handle_mode_change_request(ModeChangeRequest::SharedPtr request) = 0;
98 const VehicleStateReport & get_state_report()
const noexcept;
101 const VehicleOdometry & get_odometry()
const noexcept;
105 VehicleStateReport & state_report() noexcept;
107 VehicleOdometry & odometry() noexcept;
110 VehicleStateReport m_state_report{};
111 VehicleOdometry m_odometry{};
117 #endif // VEHICLE_INTERFACE__PLATFORM_INTERFACE_HPP_ autoware_auto_msgs::srv::AutonomyModeChange_Request ModeChangeRequest
Definition: ne_raptor_interface.hpp:120
#define VEHICLE_INTERFACE_PUBLIC
Definition: drivers/vehicle_interface/include/vehicle_interface/visibility_control.hpp:44
autoware_auto_msgs::srv::AutonomyModeChange_Response ModeChangeResponse
Definition: ne_raptor_interface.hpp:121
bool bool8_t
Definition: types.hpp:33
This file includes common type definition.
autoware_auto_msgs::msg::VehicleControlCommand VehicleControlCommand
Definition: pure_pursuit.hpp:41
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24