Autoware.Auto
|
|
#include <platform_interface.hpp>
Public Member Functions | |
PlatformInterface ()=default | |
Constructor. More... | |
virtual | ~PlatformInterface ()=default |
Destructor. More... | |
virtual bool8_t | update (std::chrono::nanoseconds timeout)=0 |
virtual bool8_t | send_state_command (const VehicleStateCommand &msg)=0 |
virtual bool8_t | send_control_command (const VehicleControlCommand &msg)=0 |
virtual bool8_t | send_control_command (const AckermannControlCommand &msg)=0 |
virtual bool8_t | send_control_command (const RawControlCommand &msg)=0 |
virtual bool8_t | handle_mode_change_request (ModeChangeRequest::SharedPtr request)=0 |
const VehicleStateReport & | get_state_report () const noexcept |
const VehicleOdometry & | get_odometry () const noexcept |
const HeadlightsReport & | get_headlights_report () const noexcept |
Get the most recent state of the headlights feature. More... | |
const HornReport & | get_horn_report () const noexcept |
Get the most recent state of the horn feature. More... | |
const WipersReport & | get_wipers_report () const noexcept |
Get the most recent state of the wipers feature. More... | |
const GearReport & | get_gear_report () const noexcept |
Get the most recent state of the gear feature. More... | |
virtual void | send_gear_command (const GearCommand &msg) |
Send the gear control command to the vehicle platform. If this is not implemented for a specific vehicle but is called, a runtime error will be thrown. More... | |
virtual void | send_hand_brake_command (const HandBrakeCommand &msg) |
Send the hand_brake control command to the vehicle platform. If this is not implemented for a specific vehicle but is called, a runtime error will be thrown. More... | |
virtual void | send_headlights_command (const HeadlightsCommand &msg) |
Send the headlight control command to the vehicle platform. If this is not implemented for a specific vehicle but is called, a runtime error will be thrown. More... | |
virtual void | send_horn_command (const HornCommand &msg) |
Send the horn control command to the vehicle platform. If this is not implemented for a specific vehicle but is called, a runtime error will be thrown. More... | |
virtual void | send_wipers_command (const WipersCommand &msg) |
Send the wipers control command to the vehicle platform. If this is not implemented for a specific vehicle but is called, a runtime error will be thrown. More... | |
virtual void | send_hazard_lights_command (const HazardLightsCommand &msg) |
Send the hazard lights control command to the vehicle platform. If this is not implemented for a specific vehicle but is called, a runtime error will be thrown. More... | |
Protected Member Functions | |
VehicleStateReport & | state_report () noexcept |
Get the underlying state report for modification. More... | |
VehicleOdometry & | odometry () noexcept |
Get the underlying odometry for modification. More... | |
HeadlightsReport & | headlights_report () noexcept |
Get the underlying headlight state for modification. More... | |
HornReport & | horn_report () noexcept |
Get the underlying horn state for modification. More... | |
WipersReport & | wipers_report () noexcept |
Get the underlying wiper state for modification. More... | |
GearReport & | gear_report () noexcept |
Get the underlying gear state 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
|
default |
Constructor.
|
virtualdefault |
Destructor.
|
protectednoexcept |
Get the underlying gear state for modification.
|
noexcept |
Get the most recent state of the gear feature.
|
noexcept |
Get the most recent state of the headlights feature.
|
noexcept |
Get the most recent state of the horn feature.
|
noexcept |
Get the most recent odomoetry of the vehicle
|
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.
|
noexcept |
Get the most recent state of the wipers feature.
|
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
[in] | request | The requested mode |
Implemented in autoware::ne_raptor_interface::NERaptorInterface, and ssc_interface::SscInterface.
|
protectednoexcept |
Get the underlying headlight state for modification.
|
protectednoexcept |
Get the underlying horn state for modification.
|
protectednoexcept |
Get the underlying odometry for modification.
|
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
[in] | msg | The control command to send to the vehicle |
Implemented in autoware::ne_raptor_interface::NERaptorInterface, ssc_interface::SscInterface, and autoware::vesc_interface::VESCInterface.
|
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
[in] | msg | The control command to send to the vehicle |
Implemented in autoware::ne_raptor_interface::NERaptorInterface, ssc_interface::SscInterface, and autoware::vesc_interface::VESCInterface.
|
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
[in] | msg | The control command to send to the vehicle |
Implemented in autoware::ne_raptor_interface::NERaptorInterface, ssc_interface::SscInterface, and autoware::vesc_interface::VESCInterface.
|
virtual |
Send the gear control command to the vehicle platform. If this is not implemented for a specific vehicle but is called, a runtime error will be thrown.
[in] | msg | The control command to send to the vehicle. |
|
virtual |
Send the hand_brake control command to the vehicle platform. If this is not implemented for a specific vehicle but is called, a runtime error will be thrown.
[in] | msg | The control command to send to the vehicle. |
|
virtual |
Send the hazard lights control command to the vehicle platform. If this is not implemented for a specific vehicle but is called, a runtime error will be thrown.
[in] | msg | The control command to send to the vehicle. |
|
virtual |
Send the headlight control command to the vehicle platform. If this is not implemented for a specific vehicle but is called, a runtime error will be thrown.
[in] | msg | The control command to send to the vehicle. |
Reimplemented in autoware::ne_raptor_interface::NERaptorInterface.
|
virtual |
Send the horn control command to the vehicle platform. If this is not implemented for a specific vehicle but is called, a runtime error will be thrown.
[in] | msg | The control command to send to the vehicle. |
Reimplemented in autoware::ne_raptor_interface::NERaptorInterface.
|
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
[in] | msg | The state command to send to the vehicle |
Implemented in autoware::ne_raptor_interface::NERaptorInterface, ssc_interface::SscInterface, and autoware::vesc_interface::VESCInterface.
|
virtual |
Send the wipers control command to the vehicle platform. If this is not implemented for a specific vehicle but is called, a runtime error will be thrown.
[in] | msg | The control command to send to the vehicle. |
Reimplemented in autoware::ne_raptor_interface::NERaptorInterface.
|
protectednoexcept |
Get the underlying state report for modification.
|
pure virtual |
Try to receive data from the vehicle platform, and update StateReport and Odometry. If no data is received, return false, and the VehicleInterfaceNode will treat this as an error If the platform supports additional sensors/messages, then publishing can happen in this method. Exceptions may be thrown on errors
[in] | timeout | The maximum amount of time to check/receive data |
Implemented in autoware::ne_raptor_interface::NERaptorInterface, lgsvl_interface::LgsvlInterface, ssc_interface::SscInterface, and autoware::vesc_interface::VESCInterface.
|
protectednoexcept |
Get the underlying wiper state for modification.