Autoware.Auto
autoware::motion::control::trajectory_follower::SmoothStop Class Reference

Smooth stop class to implement vehicle specific deceleration profiles. More...

#include <smooth_stop.hpp>

Public Member Functions

void init (const float64_t pred_vel_in_target, const float64_t pred_stop_dist)
 initialize the state of the smooth stop More...
 
void setParams (float64_t max_strong_acc, float64_t min_strong_acc, float64_t weak_acc, float64_t weak_stop_acc, float64_t strong_stop_acc, float64_t min_fast_vel, float64_t min_running_vel, float64_t min_running_acc, float64_t weak_stop_time, float64_t weak_stop_dist, float64_t strong_stop_dist)
 set the parameters of this smooth stop More...
 
std::experimental::optional< float64_t > calcTimeToStop (const std::vector< std::pair< rclcpp::Time, float64_t >> &vel_hist) const
 predict time when car stops by fitting some latest observed velocity history with linear function (v = at + b) More...
 
float64_t calculate (const float64_t stop_dist, const float64_t current_vel, const float64_t current_acc, const std::vector< std::pair< rclcpp::Time, float64_t >> &vel_hist, const float64_t delay_time)
 calculate accel command while stopping Decrease velocity with m_strong_acc, then loose brake pedal with m_params.weak_acc to stop smoothly If the car is still running, input m_params.weak_stop_acc and then m_params.strong_stop_acc in steps not to exceed stopline too much More...
 

Detailed Description

Smooth stop class to implement vehicle specific deceleration profiles.

Member Function Documentation

◆ calcTimeToStop()

std::experimental::optional< float64_t > autoware::motion::control::trajectory_follower::SmoothStop::calcTimeToStop ( const std::vector< std::pair< rclcpp::Time, float64_t >> &  vel_hist) const

predict time when car stops by fitting some latest observed velocity history with linear function (v = at + b)

Parameters
[in]vel_histhistory of previous ego velocities as (rclcpp::Time, float64_t[m/s]) pairs
Exceptions
std::runtime_errorif parameters have not been set

◆ calculate()

float64_t autoware::motion::control::trajectory_follower::SmoothStop::calculate ( const float64_t  stop_dist,
const float64_t  current_vel,
const float64_t  current_acc,
const std::vector< std::pair< rclcpp::Time, float64_t >> &  vel_hist,
const float64_t  delay_time 
)

calculate accel command while stopping Decrease velocity with m_strong_acc, then loose brake pedal with m_params.weak_acc to stop smoothly If the car is still running, input m_params.weak_stop_acc and then m_params.strong_stop_acc in steps not to exceed stopline too much

Parameters
[in]stop_distdistance left to travel before stopping [m]
[in]current_velcurrent velocity of ego [m/s]
[in]current_acccurrent acceleration of ego [m/s²]
[in]vel_histhistory of previous ego velocities as (rclcpp::Time, float64_t[m/s]) pairs
[in]delay_timeassumed time delay when the stop command will actually be executed
Exceptions
std::runtime_errorif parameters have not been set

◆ init()

void autoware::motion::control::trajectory_follower::SmoothStop::init ( const float64_t  pred_vel_in_target,
const float64_t  pred_stop_dist 
)

initialize the state of the smooth stop

Parameters
[in]pred_vel_in_targetpredicted ego velocity when the stop command will be executed
[in]pred_stop_distpredicted stop distance when the stop command will be executed

◆ setParams()

void autoware::motion::control::trajectory_follower::SmoothStop::setParams ( float64_t  max_strong_acc,
float64_t  min_strong_acc,
float64_t  weak_acc,
float64_t  weak_stop_acc,
float64_t  strong_stop_acc,
float64_t  min_fast_vel,
float64_t  min_running_vel,
float64_t  min_running_acc,
float64_t  weak_stop_time,
float64_t  weak_stop_dist,
float64_t  strong_stop_dist 
)

set the parameters of this smooth stop

Parameters
[in]max_strong_accmaximum strong acceleration value [m/s²]
[in]min_strong_accminumum strong acceleration value [m/s²]
[in]weak_accweak acceleration value [m/s²]
[in]weak_stop_accweak stopping acceleration value [m/s²]
[in]strong_stop_accstrong stopping acceleration value [m/s²]
[in]min_fast_velminumum velocity to consider ego to be running fast [m/s]
[in]min_running_velminimum velocity to consider ego to be running [m/s]
[in]min_running_accminimum acceleration to consider ego to be running [m/s]
[in]weak_stop_timetime allowed for stopping with a weak acceleration [s]
[in]weak_stop_distdistance to the stop point bellow which a weak accel is applied [m]
[in]strong_stop_distdistance to the stop point bellow which a strong accel is applied [m]

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