Autoware.Auto
autoware::drivers::vehicle_interface::PlatformInterface Class Referenceabstract

#include <platform_interface.hpp>

Inheritance diagram for autoware::drivers::vehicle_interface::PlatformInterface:

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_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...
 

Detailed Description

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

Constructor & Destructor Documentation

◆ PlatformInterface()

autoware::drivers::vehicle_interface::PlatformInterface::PlatformInterface ( )
default

Constructor.

◆ ~PlatformInterface()

virtual autoware::drivers::vehicle_interface::PlatformInterface::~PlatformInterface ( )
virtualdefault

Destructor.

Member Function Documentation

◆ gear_report()

autoware_auto_vehicle_msgs::msg::GearReport & autoware::drivers::vehicle_interface::PlatformInterface::gear_report ( )
protectednoexcept

Get the underlying gear state for modification.

◆ get_gear_report()

const autoware_auto_vehicle_msgs::msg::GearReport & autoware::drivers::vehicle_interface::PlatformInterface::get_gear_report ( ) const
noexcept

Get the most recent state of the gear feature.

Returns
A GearReport message intended to be published.

◆ get_headlights_report()

const autoware_auto_vehicle_msgs::msg::HeadlightsReport & autoware::drivers::vehicle_interface::PlatformInterface::get_headlights_report ( ) const
noexcept

Get the most recent state of the headlights feature.

Returns
A HeadlightsReport message intended to be published.

◆ get_horn_report()

const autoware_auto_vehicle_msgs::msg::HornReport & autoware::drivers::vehicle_interface::PlatformInterface::get_horn_report ( ) const
noexcept

Get the most recent state of the horn feature.

Returns
A HornReport message intended to be published.

◆ get_odometry()

const autoware_auto_vehicle_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_vehicle_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.

◆ get_wipers_report()

const autoware_auto_vehicle_msgs::msg::WipersReport & autoware::drivers::vehicle_interface::PlatformInterface::get_wipers_report ( ) const
noexcept

Get the most recent state of the wipers feature.

Returns
A WipersReport 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]requestThe 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.

◆ headlights_report()

autoware_auto_vehicle_msgs::msg::HeadlightsReport & autoware::drivers::vehicle_interface::PlatformInterface::headlights_report ( )
protectednoexcept

Get the underlying headlight state for modification.

◆ horn_report()

autoware_auto_vehicle_msgs::msg::HornReport & autoware::drivers::vehicle_interface::PlatformInterface::horn_report ( )
protectednoexcept

Get the underlying horn state for modification.

◆ odometry()

autoware_auto_vehicle_msgs::msg::VehicleOdometry & autoware::drivers::vehicle_interface::PlatformInterface::odometry ( )
protectednoexcept

Get the underlying odometry for modification.

◆ send_control_command() [1/3]

virtual bool8_t autoware::drivers::vehicle_interface::PlatformInterface::send_control_command ( const AckermannControlCommand &  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]msgThe 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/3]

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]msgThe 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() [3/3]

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]msgThe 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_hand_brake_command()

void autoware::drivers::vehicle_interface::PlatformInterface::send_hand_brake_command ( const HandBrakeCommand &  msg)
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.

Parameters
[in]msgThe control command to send to the vehicle.

◆ send_hazard_lights_command()

void autoware::drivers::vehicle_interface::PlatformInterface::send_hazard_lights_command ( const HazardLightsCommand &  msg)
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.

Parameters
[in]msgThe control command to send to the vehicle.

◆ send_headlights_command()

void autoware::drivers::vehicle_interface::PlatformInterface::send_headlights_command ( const HeadlightsCommand &  msg)
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.

Parameters
[in]msgThe control command to send to the vehicle.

Reimplemented in autoware::ne_raptor_interface::NERaptorInterface.

◆ send_horn_command()

void autoware::drivers::vehicle_interface::PlatformInterface::send_horn_command ( const HornCommand &  msg)
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.

Parameters
[in]msgThe control command to send to the vehicle.

Reimplemented in autoware::ne_raptor_interface::NERaptorInterface.

◆ 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]msgThe 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.

◆ send_wipers_command()

void autoware::drivers::vehicle_interface::PlatformInterface::send_wipers_command ( const WipersCommand &  msg)
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.

Parameters
[in]msgThe control command to send to the vehicle.

Reimplemented in autoware::ne_raptor_interface::NERaptorInterface.

◆ state_report()

autoware_auto_vehicle_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

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

Parameters
[in]timeoutThe maximum amount of time to check/receive data
Returns
True if data was received before the timeout, false otherwise

Implemented in autoware::ne_raptor_interface::NERaptorInterface, lgsvl_interface::LgsvlInterface, and ssc_interface::SscInterface.

◆ wipers_report()

autoware_auto_vehicle_msgs::msg::WipersReport & autoware::drivers::vehicle_interface::PlatformInterface::wipers_report ( )
protectednoexcept

Get the underlying wiper state for modification.


The documentation for this class was generated from the following files: