Autoware.Auto
|
|
Class for interfacing with NE Raptor DBW. More...
#include <ne_raptor_interface.hpp>
Public Member Functions | |
NERaptorInterface (rclcpp::Node &node, uint16_t ecu_build_num, float32_t front_axle_to_cog, float32_t rear_axle_to_cog, float32_t steer_to_tire_ratio, float32_t max_steer_angle, float32_t acceleration_limit, float32_t deceleration_limit, float32_t acceleration_positive_jerk_limit, float32_t deceleration_negative_jerk_limit, uint32_t pub_period) | |
Default constructor. More... | |
~NERaptorInterface () noexcept override=default | |
Default destructor. More... | |
bool8_t | update (std::chrono::nanoseconds timeout) override |
Try to receive data from the vehicle platform, and update StateReport and Odometry. Exceptions may be thrown on errors. More... | |
bool8_t | send_state_command (const VehicleStateCommand &msg) override |
Send the state command to the vehicle platform. Exceptions may be thrown on errors. More... | |
bool8_t | send_control_command (const HighLevelControlCommand &msg) |
Send the control command to the vehicle platform. Exceptions may be thrown on errors. More... | |
bool8_t | send_control_command (const RawControlCommand &msg) override |
Send the control command to the vehicle platform. Exceptions may be thrown on errors. More... | |
bool8_t | send_control_command (const VehicleControlCommand &msg) override |
Send the control command to the vehicle platform. Exceptions may be thrown on errors Steering -> tire angle conversion is linear except for extreme angles. More... | |
bool8_t | send_control_command (const AckermannControlCommand &msg) override |
Send the control command to the vehicle platform. Exceptions may be thrown on errors Steering -> tire angle conversion is linear except for extreme angles. More... | |
bool8_t | handle_mode_change_request (ModeChangeRequest::SharedPtr request) override |
Handle a request from the user to enable or disable the DBW system. Exceptions may be thrown on errors. More... | |
void | send_headlights_command (const HeadlightsCommand &msg) override |
Send a headlights command to the vehicle platform. More... | |
void | send_horn_command (const HornCommand &msg) override |
Send a horn command to the vehicle platform. More... | |
void | send_wipers_command (const WipersCommand &msg) override |
Send a wipers command to the vehicle platform. More... | |
void | kinematic_bicycle_model (float32_t dt, VehicleKinematicState *vks) |
Update vehicle's position & heading relative from time = 0 based on time difference, current speed, & current tire angle. More... | |
Public Member Functions inherited from autoware::drivers::vehicle_interface::PlatformInterface | |
PlatformInterface ()=default | |
Constructor. More... | |
virtual | ~PlatformInterface ()=default |
Destructor. More... | |
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_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... | |
Class for interfacing with NE Raptor DBW.
|
explicit |
Default constructor.
[in] | node | Reference to node |
[in] | ecu_build_num | ECU build # |
[in] | front_axle_to_cog | Distance from front axle to center-of-gravity in meters |
[in] | rear_axle_to_cog | Distance from rear axle to center-of-gravity in meters |
[in] | steer_to_tire_ratio | Ratio of steering angle / car tire angle |
[in] | max_steer_angle | Maximum steering wheel turn angle |
[in] | acceleration_limit | m/s^2, zero = no limit |
[in] | deceleration_limit | m/s^2, zero = no limit |
[in] | acceleration_positive_jerk_limit | m/s^3 |
[in] | deceleration_negative_jerk_limit | m/s^3 |
[in] | pub_period | message publishing period, in milliseconds |
|
overridedefaultnoexcept |
Default destructor.
|
overridevirtual |
Handle a request from the user to enable or disable the DBW system. Exceptions may be thrown on errors.
[in] | request | The requested autonomy mode |
Implements autoware::drivers::vehicle_interface::PlatformInterface.
void autoware::ne_raptor_interface::NERaptorInterface::kinematic_bicycle_model | ( | float32_t | dt, |
VehicleKinematicState * | vks | ||
) |
Update vehicle's position & heading relative from time = 0 based on time difference, current speed, & current tire angle.
[in] | dt | delta-T - how much time since this was last called |
[in,out] | vks | the current vehicle kinematic state (contains current motion data) |
|
overridevirtual |
Send the control command to the vehicle platform. Exceptions may be thrown on errors Steering -> tire angle conversion is linear except for extreme angles.
[in] | msg | The control command to send to the vehicle |
Implements autoware::drivers::vehicle_interface::PlatformInterface.
bool8_t autoware::ne_raptor_interface::NERaptorInterface::send_control_command | ( | const HighLevelControlCommand & | msg | ) |
Send the control command to the vehicle platform. Exceptions may be thrown on errors.
[in] | msg | The control command to send to the vehicle |
|
overridevirtual |
Send the control command to the vehicle platform. Exceptions may be thrown on errors.
[in] | msg | The control command to send to the vehicle |
Implements autoware::drivers::vehicle_interface::PlatformInterface.
|
overridevirtual |
Send the control command to the vehicle platform. Exceptions may be thrown on errors Steering -> tire angle conversion is linear except for extreme angles.
[in] | msg | The control command to send to the vehicle |
Implements autoware::drivers::vehicle_interface::PlatformInterface.
|
overridevirtual |
Send a headlights command to the vehicle platform.
[in] | msg | The headlights command to send to the vehicle |
Reimplemented from autoware::drivers::vehicle_interface::PlatformInterface.
|
overridevirtual |
Send a horn command to the vehicle platform.
[in] | msg | The horn command to send to the vehicle |
Reimplemented from autoware::drivers::vehicle_interface::PlatformInterface.
|
overridevirtual |
Send the state command to the vehicle platform. Exceptions may be thrown on errors.
[in] | msg | The state command to send to the vehicle |
Implements autoware::drivers::vehicle_interface::PlatformInterface.
|
overridevirtual |
Send a wipers command to the vehicle platform.
[in] | msg | The wipers command to send to the vehicle |
Reimplemented from autoware::drivers::vehicle_interface::PlatformInterface.
|
overridevirtual |
Try to receive data from the vehicle platform, and update StateReport and Odometry. Exceptions may be thrown on errors.
[in] | timeout | The maximum amount of time to check/receive data |
Implements autoware::drivers::vehicle_interface::PlatformInterface.