#include <st_driving_limits.h>
|
| | STDrivingLimits () |
| |
| void | Init (const double max_acc, const double max_dec, const double max_v, double curr_v) |
| |
| virtual | ~STDrivingLimits ()=default |
| |
| std::pair< double, double > | GetVehicleDynamicsLimits (const double t) const |
| | Given time t, calculate the driving limits in s due to vehicle's dynamics. More...
|
| |
| void | UpdateBlockingInfo (const double t, const double lower_s, const double lower_v, const double upper_s, const double upper_v) |
| | Update the anchoring of the vehicle dynamics limits. For example, when ADC is blocked by some obstacle, its max. drivable area, max. speed, etc. are also limited subsequently. More...
|
| |
◆ STDrivingLimits()
| apollo::planning::STDrivingLimits::STDrivingLimits |
( |
| ) |
|
|
inline |
◆ ~STDrivingLimits()
| virtual apollo::planning::STDrivingLimits::~STDrivingLimits |
( |
| ) |
|
|
virtualdefault |
◆ GetVehicleDynamicsLimits()
| std::pair<double, double> apollo::planning::STDrivingLimits::GetVehicleDynamicsLimits |
( |
const double |
t | ) |
const |
Given time t, calculate the driving limits in s due to vehicle's dynamics.
- Parameters
-
- Returns
- The lower and upper bounds.
◆ Init()
| void apollo::planning::STDrivingLimits::Init |
( |
const double |
max_acc, |
|
|
const double |
max_dec, |
|
|
const double |
max_v, |
|
|
double |
curr_v |
|
) |
| |
◆ UpdateBlockingInfo()
| void apollo::planning::STDrivingLimits::UpdateBlockingInfo |
( |
const double |
t, |
|
|
const double |
lower_s, |
|
|
const double |
lower_v, |
|
|
const double |
upper_s, |
|
|
const double |
upper_v |
|
) |
| |
Update the anchoring of the vehicle dynamics limits. For example, when ADC is blocked by some obstacle, its max. drivable area, max. speed, etc. are also limited subsequently.
- Parameters
-
| Time | t |
| lower | bound in s |
| lower | bound's corresponding speed. |
| upper | bound in s |
| upper | bound's corresponding speed. |
The documentation for this class was generated from the following file: