#include <platform_interface.hpp>
|
| VehicleStateReport & | state_report () noexcept |
| | Get the underlying state report for modification. More...
|
| |
| VehicleOdometry & | odometry () noexcept |
| | Get the underlying odometry for modification. More...
|
| |
Interface class for specific vehicle implementations. Child classes which implement this interface are expected to have wrap their own communication mechanism, and create a subclass from the VehicleInterfaceNode
◆ PlatformInterface()
| autoware::drivers::vehicle_interface::PlatformInterface::PlatformInterface |
( |
| ) |
|
|
default |
◆ ~PlatformInterface()
| virtual autoware::drivers::vehicle_interface::PlatformInterface::~PlatformInterface |
( |
| ) |
|
|
virtualdefault |
◆ get_odometry()
| const autoware_auto_msgs::msg::VehicleOdometry & autoware::drivers::vehicle_interface::PlatformInterface::get_odometry |
( |
| ) |
const |
|
noexcept |
Get the most recent odomoetry of the vehicle
- Returns
- A Odometry message intended to be published.
◆ get_state_report()
| const autoware_auto_msgs::msg::VehicleStateReport & autoware::drivers::vehicle_interface::PlatformInterface::get_state_report |
( |
| ) |
const |
|
noexcept |
Get the most recent state of the vehicle. The State should be assumed to be constant unless data from the vehicle platform implies a state should be changed. For example, if the gear state is drive, the StateReport should be in drive until the vehicle platform reports that it is in neutral or some other gear state.
- Returns
- A StateReport message intended to be published.
◆ handle_mode_change_request()
| virtual bool8_t autoware::drivers::vehicle_interface::PlatformInterface::handle_mode_change_request |
( |
ModeChangeRequest::SharedPtr |
request | ) |
|
|
pure virtual |
Respond to a request to change the autonomy mode. This should only fail if changing the mode on the actual low-level autonomy interface fails. Exceptions may be thrown on errors
- Parameters
-
| [in] | request | The requested mode |
- Returns
- false If changing the mode failed in some way, true otherwise
Implemented in autoware::ne_raptor_interface::NERaptorInterface, and ssc_interface::SscInterface.
◆ odometry()
| autoware_auto_msgs::msg::VehicleOdometry & autoware::drivers::vehicle_interface::PlatformInterface::odometry |
( |
| ) |
|
|
protectednoexcept |
Get the underlying odometry for modification.
◆ send_control_command() [1/2]
| virtual bool8_t autoware::drivers::vehicle_interface::PlatformInterface::send_control_command |
( |
const RawControlCommand & |
msg | ) |
|
|
pure virtual |
Send the state command to the vehicle platform. May require translation into a vehicle-specific representation and sending multiple messages. Exceptions may be thrown on errors
- Parameters
-
| [in] | msg | The control command to send to the vehicle |
- Returns
- false if sending failed in some way, true otherwise
Implemented in autoware::ne_raptor_interface::NERaptorInterface, and ssc_interface::SscInterface.
◆ send_control_command() [2/2]
| virtual bool8_t autoware::drivers::vehicle_interface::PlatformInterface::send_control_command |
( |
const VehicleControlCommand & |
msg | ) |
|
|
pure virtual |
Send the state command to the vehicle platform. May require translation into a vehicle-specific representation and sending multiple messages. Exceptions may be thrown on errors
- Parameters
-
| [in] | msg | The control command to send to the vehicle |
- Returns
- false if sending failed in some way, true otherwise
Implemented in autoware::ne_raptor_interface::NERaptorInterface, and ssc_interface::SscInterface.
◆ send_state_command()
| virtual bool8_t autoware::drivers::vehicle_interface::PlatformInterface::send_state_command |
( |
const VehicleStateCommand & |
msg | ) |
|
|
pure virtual |
Send the state command to the vehicle platform. May require translation into a vehicle-specific representation and sending multiple messages Exceptions may be thrown on errors
- Parameters
-
| [in] | msg | The state command to send to the vehicle |
- Returns
- false if sending failed in some way, true otherwise
Implemented in autoware::ne_raptor_interface::NERaptorInterface, and ssc_interface::SscInterface.
◆ state_report()
| autoware_auto_msgs::msg::VehicleStateReport & autoware::drivers::vehicle_interface::PlatformInterface::state_report |
( |
| ) |
|
|
protectednoexcept |
Get the underlying state report for modification.
◆ update()
| virtual bool8_t autoware::drivers::vehicle_interface::PlatformInterface::update |
( |
std::chrono::nanoseconds |
timeout | ) |
|
|
pure virtual |
The documentation for this class was generated from the following files: