ADORe
ADORe is a modular open source software library and toolkit for decision making, planning, control and simulation of automated vehicles
adore::if_ROS::params::PLateralPlanner Class Reference

#include <p_lateral_planner.h>

Inheritance diagram for adore::if_ROS::params::PLateralPlanner:
Inheritance graph
Collaboration diagram for adore::if_ROS::params::PLateralPlanner:
Collaboration graph

Public Member Functions

 PLateralPlanner (ros::NodeHandle n, std::string prefix)
 
virtual double getWeightPos () const override
 getWeightPos returns cost function weight for quadratic position error term More...
 
virtual double getWeightVel () const override
 getWeightVel returns cost function weight for quadratic velocity error term More...
 
virtual double getWeightAcc () const override
 getWeightAcc returns cost function weight for quadratic acceleration term More...
 
virtual double getWeightJerk () const override
 getWeightJerk returns cost function weight for quadratic jerk term More...
 
virtual double getWeightEndPos () const override
 getWeightEndPos returns cost function weight for quadratic position error term at end point More...
 
virtual double getWeightEndVel () const override
 getWeightEndVel returns cost function weight for quadratic velocity error term at end point More...
 
virtual double getWeightEndAcc () const override
 getWeightEndAcc returns cost function weight for quadratic acceleration term at end point More...
 
virtual double getSlackPos () const override
 getSlackPos returns maximum slack of soft-constraints for position More...
 
virtual double getSlackVel () const override
 getSlackVel returns maximum slack of soft-constraints for velocity More...
 
virtual double getSlackAcc () const override
 getSlackAcc returns maximum slack of soft-constraints for acceleration More...
 
virtual double getAccLB () const override
 getAccLB returns lateral acceleration lower bound More...
 
virtual double getAccUB () const override
 getAccUB returns lateral acceleration upper bound More...
 
virtual double getJerkLB () const override
 getJerkLB returns lateral jerk lower bound More...
 
virtual double getJerkUB () const override
 getJerkLB returns lateral jerk upper bound More...
 
virtual double getCurvatureUB () const override
 getCurvatureUB returns maximum curvature of path (relevant at low speeds) More...
 
virtual double getCurvatureLB () const override
 getCurvatureLB returns minimum curvature of path (relevant at low speeds) More...
 
virtual double getRelativeHeadingUB () const override
 getRelativeHeadingUB returns upper bound on heading deviation from current lane's coordinate system More...
 
virtual double getRelativeHeadingLB () const override
 getRelativeHeadingLB returns lower bound on heading deviation from current lane's coordinate system More...
 
virtual double getMergeConstraintDelay () const override
 getMergeConstraintDelay returns a time-delay after which lateral position constraints are activated, if they are initially violated More...
 
virtual double getHardSafetyDistanceToLaneBoundary () const override
 getHardSafetyDistanceToLaneBoundary returns the minimum distance between lane boundary and vehicle side More...
 
virtual double getSoftSafetyDistanceToLaneBoundary () const override
 getSoftSafetyDistanceToLaneBoundary returns the minimum distance between lane boundary and vehicle side, which is enforced, if sufficient space is available More...
 
virtual double getMinimumLateralControlSpace () const override
 getMinimumLateralControlSpace returns the minimum desired lateral control space: If vehicle has more space for lateral control, softSafetyDistanceToLaneBoundary is enforced More...
 
virtual double getMaxCPUTime () const override
 getMaxCPUTime returns the maximum cpu time for one plan computation More...
 
virtual double getLateralGridScale () const override
 getLateralGridScale returns the size of a grid step d for lateral variations of a maneuver: maneuver variations will plan for offsets {...,-2d,-d,0,d,2d,..} More...
 

Additional Inherited Members

- Private Member Functions inherited from adore::if_ROS::ROSParam
template<typename T >
void get (const std::string &name, T &result) const
 
 ROSParam (ros::NodeHandle n, std::string prefix)
 
- Private Attributes inherited from adore::if_ROS::ROSParam
std::string prefix_
 
ros::NodeHandle n_
 

Constructor & Destructor Documentation

◆ PLateralPlanner()

adore::if_ROS::params::PLateralPlanner::PLateralPlanner ( ros::NodeHandle  n,
std::string  prefix 
)
inline

Member Function Documentation

◆ getAccLB()

virtual double adore::if_ROS::params::PLateralPlanner::getAccLB ( ) const
inlineoverridevirtual

getAccLB returns lateral acceleration lower bound

Implements adore::params::APLateralPlanner.

Here is the call graph for this function:

◆ getAccUB()

virtual double adore::if_ROS::params::PLateralPlanner::getAccUB ( ) const
inlineoverridevirtual

getAccUB returns lateral acceleration upper bound

Implements adore::params::APLateralPlanner.

Here is the call graph for this function:

◆ getCurvatureLB()

virtual double adore::if_ROS::params::PLateralPlanner::getCurvatureLB ( ) const
inlineoverridevirtual

getCurvatureLB returns minimum curvature of path (relevant at low speeds)

Implements adore::params::APLateralPlanner.

Here is the call graph for this function:

◆ getCurvatureUB()

virtual double adore::if_ROS::params::PLateralPlanner::getCurvatureUB ( ) const
inlineoverridevirtual

getCurvatureUB returns maximum curvature of path (relevant at low speeds)

Implements adore::params::APLateralPlanner.

Here is the call graph for this function:

◆ getHardSafetyDistanceToLaneBoundary()

virtual double adore::if_ROS::params::PLateralPlanner::getHardSafetyDistanceToLaneBoundary ( ) const
inlineoverridevirtual

getHardSafetyDistanceToLaneBoundary returns the minimum distance between lane boundary and vehicle side

Implements adore::params::APLateralPlanner.

Here is the call graph for this function:

◆ getJerkLB()

virtual double adore::if_ROS::params::PLateralPlanner::getJerkLB ( ) const
inlineoverridevirtual

getJerkLB returns lateral jerk lower bound

Implements adore::params::APLateralPlanner.

Here is the call graph for this function:

◆ getJerkUB()

virtual double adore::if_ROS::params::PLateralPlanner::getJerkUB ( ) const
inlineoverridevirtual

getJerkLB returns lateral jerk upper bound

Implements adore::params::APLateralPlanner.

Here is the call graph for this function:

◆ getLateralGridScale()

virtual double adore::if_ROS::params::PLateralPlanner::getLateralGridScale ( ) const
inlineoverridevirtual

getLateralGridScale returns the size of a grid step d for lateral variations of a maneuver: maneuver variations will plan for offsets {...,-2d,-d,0,d,2d,..}

Implements adore::params::APLateralPlanner.

Here is the call graph for this function:

◆ getMaxCPUTime()

virtual double adore::if_ROS::params::PLateralPlanner::getMaxCPUTime ( ) const
inlineoverridevirtual

getMaxCPUTime returns the maximum cpu time for one plan computation

Implements adore::params::APLateralPlanner.

Here is the call graph for this function:

◆ getMergeConstraintDelay()

virtual double adore::if_ROS::params::PLateralPlanner::getMergeConstraintDelay ( ) const
inlineoverridevirtual

getMergeConstraintDelay returns a time-delay after which lateral position constraints are activated, if they are initially violated

Implements adore::params::APLateralPlanner.

Here is the call graph for this function:

◆ getMinimumLateralControlSpace()

virtual double adore::if_ROS::params::PLateralPlanner::getMinimumLateralControlSpace ( ) const
inlineoverridevirtual

getMinimumLateralControlSpace returns the minimum desired lateral control space: If vehicle has more space for lateral control, softSafetyDistanceToLaneBoundary is enforced

Implements adore::params::APLateralPlanner.

Here is the call graph for this function:

◆ getRelativeHeadingLB()

virtual double adore::if_ROS::params::PLateralPlanner::getRelativeHeadingLB ( ) const
inlineoverridevirtual

getRelativeHeadingLB returns lower bound on heading deviation from current lane's coordinate system

Implements adore::params::APLateralPlanner.

Here is the call graph for this function:

◆ getRelativeHeadingUB()

virtual double adore::if_ROS::params::PLateralPlanner::getRelativeHeadingUB ( ) const
inlineoverridevirtual

getRelativeHeadingUB returns upper bound on heading deviation from current lane's coordinate system

Implements adore::params::APLateralPlanner.

Here is the call graph for this function:

◆ getSlackAcc()

virtual double adore::if_ROS::params::PLateralPlanner::getSlackAcc ( ) const
inlineoverridevirtual

getSlackAcc returns maximum slack of soft-constraints for acceleration

Implements adore::params::APLateralPlanner.

Here is the call graph for this function:

◆ getSlackPos()

virtual double adore::if_ROS::params::PLateralPlanner::getSlackPos ( ) const
inlineoverridevirtual

getSlackPos returns maximum slack of soft-constraints for position

Implements adore::params::APLateralPlanner.

Here is the call graph for this function:

◆ getSlackVel()

virtual double adore::if_ROS::params::PLateralPlanner::getSlackVel ( ) const
inlineoverridevirtual

getSlackVel returns maximum slack of soft-constraints for velocity

Implements adore::params::APLateralPlanner.

Here is the call graph for this function:

◆ getSoftSafetyDistanceToLaneBoundary()

virtual double adore::if_ROS::params::PLateralPlanner::getSoftSafetyDistanceToLaneBoundary ( ) const
inlineoverridevirtual

getSoftSafetyDistanceToLaneBoundary returns the minimum distance between lane boundary and vehicle side, which is enforced, if sufficient space is available

Implements adore::params::APLateralPlanner.

Here is the call graph for this function:

◆ getWeightAcc()

virtual double adore::if_ROS::params::PLateralPlanner::getWeightAcc ( ) const
inlineoverridevirtual

getWeightAcc returns cost function weight for quadratic acceleration term

Implements adore::params::APLateralPlanner.

Here is the call graph for this function:

◆ getWeightEndAcc()

virtual double adore::if_ROS::params::PLateralPlanner::getWeightEndAcc ( ) const
inlineoverridevirtual

getWeightEndAcc returns cost function weight for quadratic acceleration term at end point

Implements adore::params::APLateralPlanner.

Here is the call graph for this function:

◆ getWeightEndPos()

virtual double adore::if_ROS::params::PLateralPlanner::getWeightEndPos ( ) const
inlineoverridevirtual

getWeightEndPos returns cost function weight for quadratic position error term at end point

Implements adore::params::APLateralPlanner.

Here is the call graph for this function:

◆ getWeightEndVel()

virtual double adore::if_ROS::params::PLateralPlanner::getWeightEndVel ( ) const
inlineoverridevirtual

getWeightEndVel returns cost function weight for quadratic velocity error term at end point

Implements adore::params::APLateralPlanner.

Here is the call graph for this function:

◆ getWeightJerk()

virtual double adore::if_ROS::params::PLateralPlanner::getWeightJerk ( ) const
inlineoverridevirtual

getWeightJerk returns cost function weight for quadratic jerk term

Implements adore::params::APLateralPlanner.

Here is the call graph for this function:

◆ getWeightPos()

virtual double adore::if_ROS::params::PLateralPlanner::getWeightPos ( ) const
inlineoverridevirtual

getWeightPos returns cost function weight for quadratic position error term

Implements adore::params::APLateralPlanner.

Here is the call graph for this function:

◆ getWeightVel()

virtual double adore::if_ROS::params::PLateralPlanner::getWeightVel ( ) const
inlineoverridevirtual

getWeightVel returns cost function weight for quadratic velocity error term

Implements adore::params::APLateralPlanner.

Here is the call graph for this function:

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