#include <basicconstraintsandreferences.h>
NominalReferenceSpeed - use this reference for unconstrained nominal planning - maximize speed
◆ NominalReferenceSpeed()
◆ getDerivative()
virtual int adore::fun::NominalReferenceSpeed::getDerivative |
( |
| ) |
|
|
inlineoverridevirtual |
Determine for which derivative of given dimension this reference is responsible.
- Returns
- applicable to which state derivative
Implements adore::fun::ANominalReference.
◆ getDimension()
virtual int adore::fun::NominalReferenceSpeed::getDimension |
( |
| ) |
|
|
inlineoverridevirtual |
Determine for which dimension this reference is responsible (e.g. longitudinal, lateral, etc.)
- Returns
- applicable to which dimension, depends on setup of planner
Implements adore::fun::ANominalReference.
◆ getValueIfAvailable()
virtual bool adore::fun::NominalReferenceSpeed::getValueIfAvailable |
( |
double |
t, |
|
|
double |
s, |
|
|
double |
ds, |
|
|
double & |
ref |
|
) |
| const |
|
inlineoverridevirtual |
Determine whether a reference is available and retrieve its value.
- Parameters
-
t | time |
s | progress along coordinate system |
- Returns
- true, if a reference is available
Implements adore::fun::ANominalReference.
◆ setSpeedScale()
void adore::fun::NominalReferenceSpeed::setSpeedScale |
( |
double |
value | ) |
|
|
inline |
◆ update()
virtual void adore::fun::NominalReferenceSpeed::update |
( |
double |
t0, |
|
|
double |
s0, |
|
|
double |
ds0 |
|
) |
| |
|
inlineoverridevirtual |
Refresh values of the reference object. Allows parameters and precomputations to buffered for one planning cycle.
- Parameters
-
t0 | start time for planning |
s0 | start progress in road-relative coordinate system |
ds0 | derivative of s at t0 |
Implements adore::fun::ANominalReference.
◆ constraintClearance_
double adore::fun::NominalReferenceSpeed::constraintClearance_ |
|
private |
◆ curvatureSpeedLimit_
◆ lfv_
◆ lFVSpeedLimit_
◆ plon_
◆ speed_scale_
double adore::fun::NominalReferenceSpeed::speed_scale_ |
|
private |
speed_scale_ allows to drive (cautiosly) at a certain percentage of the maximum speed
The documentation for this class was generated from the following file: