Autoware.Auto
lgsvl_interface::LgsvlInterface Class Reference

#include <lgsvl_interface.hpp>

Inheritance diagram for lgsvl_interface::LgsvlInterface:
Collaboration diagram for lgsvl_interface::LgsvlInterface:

Public Member Functions

 LgsvlInterface (rclcpp::Node &node, const std::string &sim_cmd_topic, const std::string &sim_state_cmd_topic, const std::string &sim_state_report_topic, const std::string &sim_nav_odom_topic, const std::string &sim_veh_odom_topic, const std::string &kinematic_state_topic, const std::string &sim_odom_child_frame, Table1D &&throttle_table, Table1D &&brake_table, Table1D &&steer_table, bool publish_tf=NO_PUBLISH, bool publish_pose=PUBLISH)
 
 ~LgsvlInterface () noexcept override=default
 
bool update (std::chrono::nanoseconds timeout) override
 
bool send_state_command (const autoware_auto_vehicle_msgs::msg::VehicleStateCommand &msg) override
 
bool send_control_command (const autoware_auto_vehicle_msgs::msg::VehicleControlCommand &msg) override
 Send control command data with whatever state data came along last. More...
 
bool send_control_command (const autoware_auto_control_msgs::msg::AckermannControlCommand &msg) override
 Send control command data with whatever state data came along last. More...
 
bool send_control_command (const autoware_auto_vehicle_msgs::msg::RawControlCommand &msg) override
 
bool handle_mode_change_request (autoware_auto_vehicle_msgs::srv::AutonomyModeChange_Request::SharedPtr request) override
 Respond to request for changing autonomy mode. For LGSVL, this means nothing. More...
 
void send_headlights_command (const autoware_auto_vehicle_msgs::msg::HeadlightsCommand &msg) override
 Send headlights command data. More...
 
void send_horn_command (const autoware_auto_vehicle_msgs::msg::HornCommand &msg) override
 Send horn command data. More...
 
void send_wipers_command (const autoware_auto_vehicle_msgs::msg::WipersCommand &msg) override
 Send wipers command data. More...
 
- Public Member Functions inherited from autoware::drivers::vehicle_interface::PlatformInterface
 PlatformInterface ()=default
 Constructor. More...
 
virtual ~PlatformInterface ()=default
 Destructor. More...
 
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...
 

Additional Inherited Members

- Protected Member Functions inherited from autoware::drivers::vehicle_interface::PlatformInterface
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

Platform interface implementation for LGSVL. Bridges data to and from the simulator where custom logic is required to get simulator data to adhere to ROS conventions. For a full list of behaviors, see SVL simulator

Constructor & Destructor Documentation

◆ LgsvlInterface()

lgsvl_interface::LgsvlInterface::LgsvlInterface ( rclcpp::Node &  node,
const std::string &  sim_cmd_topic,
const std::string &  sim_state_cmd_topic,
const std::string &  sim_state_report_topic,
const std::string &  sim_nav_odom_topic,
const std::string &  sim_veh_odom_topic,
const std::string &  kinematic_state_topic,
const std::string &  sim_odom_child_frame,
Table1D &&  throttle_table,
Table1D &&  brake_table,
Table1D &&  steer_table,
bool  publish_tf = NO_PUBLISH,
bool  publish_pose = PUBLISH 
)

◆ ~LgsvlInterface()

lgsvl_interface::LgsvlInterface::~LgsvlInterface ( )
overridedefaultnoexcept

Member Function Documentation

◆ handle_mode_change_request()

bool8_t lgsvl_interface::LgsvlInterface::handle_mode_change_request ( autoware_auto_vehicle_msgs::srv::AutonomyModeChange_Request::SharedPtr  request)
override

Respond to request for changing autonomy mode. For LGSVL, this means nothing.

◆ send_control_command() [1/3]

bool8_t lgsvl_interface::LgsvlInterface::send_control_command ( const autoware_auto_control_msgs::msg::AckermannControlCommand &  msg)
override

Send control command data with whatever state data came along last.

◆ send_control_command() [2/3]

bool8_t lgsvl_interface::LgsvlInterface::send_control_command ( const autoware_auto_vehicle_msgs::msg::RawControlCommand &  msg)
override

Send control data with whatever state data came along last; applies scaling here too. If both brake and throttle is nonzero, decide based on config

◆ send_control_command() [3/3]

bool8_t lgsvl_interface::LgsvlInterface::send_control_command ( const autoware_auto_vehicle_msgs::msg::VehicleControlCommand &  msg)
override

Send control command data with whatever state data came along last.

◆ send_headlights_command()

void lgsvl_interface::LgsvlInterface::send_headlights_command ( const autoware_auto_vehicle_msgs::msg::HeadlightsCommand &  msg)
override

Send headlights command data.

lgsvl_msgs values are shifted down one from autoware_auto_vehicle_msgs values However, lgsvl_msgs values have no "NO_COMMAND" option so 0 is ignored

◆ send_horn_command()

void lgsvl_interface::LgsvlInterface::send_horn_command ( const autoware_auto_vehicle_msgs::msg::HornCommand &  msg)
override

Send horn command data.

◆ send_state_command()

bool8_t lgsvl_interface::LgsvlInterface::send_state_command ( const autoware_auto_vehicle_msgs::msg::VehicleStateCommand &  msg)
override

Queues up data to be sent along with the next control command. Only gear shifting between drive and reverse is supported at this time.

◆ send_wipers_command()

void lgsvl_interface::LgsvlInterface::send_wipers_command ( const autoware_auto_vehicle_msgs::msg::WipersCommand &  msg)
override

Send wipers command data.

lgsvl_msgs values are shifted down one from autoware_auto_vehicle_msgs values However, lgsvl_msgs values have no "NO_COMMAND" option so 0 is ignored

◆ update()

bool8_t lgsvl_interface::LgsvlInterface::update ( std::chrono::nanoseconds  timeout)
overridevirtual

Receives data from ROS 2 subscriber, and updates output messages. Not yet implemented

Implements autoware::drivers::vehicle_interface::PlatformInterface.


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