abstract class containing parameters related to configuring the lateral planner
Definition: ap_lateral_planner.h:26
virtual double getMinimumLateralControlSpace() const =0
getMinimumLateralControlSpace returns the minimum desired lateral control space: If vehicle has more ...
virtual double getRelativeHeadingUB() const =0
getRelativeHeadingUB returns upper bound on heading deviation from current lane's coordinate system
virtual double getJerkLB() const =0
getJerkLB returns lateral jerk lower bound
virtual double getWeightEndAcc() const =0
getWeightEndAcc returns cost function weight for quadratic acceleration term at end point
virtual double getSlackAcc() const =0
getSlackAcc returns maximum slack of soft-constraints for acceleration
virtual double getAccLB() const =0
getAccLB returns lateral acceleration lower bound
virtual double getAccUB() const =0
getAccUB returns lateral acceleration upper bound
virtual double getSlackVel() const =0
getSlackVel returns maximum slack of soft-constraints for velocity
virtual double getSlackPos() const =0
getSlackPos returns maximum slack of soft-constraints for position
virtual double getWeightAcc() const =0
getWeightAcc returns cost function weight for quadratic acceleration term
virtual double getLateralGridScale() const =0
getLateralGridScale returns the size of a grid step d for lateral variations of a maneuver: maneuver ...
virtual double getWeightVel() const =0
getWeightVel returns cost function weight for quadratic velocity error term
virtual double getJerkUB() const =0
getJerkLB returns lateral jerk upper bound
virtual double getCurvatureUB() const =0
getCurvatureUB returns maximum curvature of path (relevant at low speeds)
virtual double getCurvatureLB() const =0
getCurvatureLB returns minimum curvature of path (relevant at low speeds)
virtual double getHardSafetyDistanceToLaneBoundary() const =0
getHardSafetyDistanceToLaneBoundary returns the minimum distance between lane boundary and vehicle si...
virtual double getWeightEndVel() const =0
getWeightEndVel returns cost function weight for quadratic velocity error term at end point
virtual double getMergeConstraintDelay() const =0
getMergeConstraintDelay returns a time-delay after which lateral position constraints are activated,...
virtual double getSoftSafetyDistanceToLaneBoundary() const =0
getSoftSafetyDistanceToLaneBoundary returns the minimum distance between lane boundary and vehicle si...
virtual double getMaxCPUTime() const =0
getMaxCPUTime returns the maximum cpu time for one plan computation
virtual double getWeightPos() const =0
getWeightPos returns cost function weight for quadratic position error term
virtual double getWeightEndPos() const =0
getWeightEndPos returns cost function weight for quadratic position error term at end point
virtual double getRelativeHeadingLB() const =0
getRelativeHeadingLB returns lower bound on heading deviation from current lane's coordinate system
virtual double getWeightJerk() const =0
getWeightJerk returns cost function weight for quadratic jerk term
Definition: areaofeffectconverter.h:20