abstract class containing parameters related to configuring the longitudinal planner More...
#include <ap_longitudinal_planner.h>
Public Member Functions | |
virtual double | getWeightPos () const =0 |
getWeightPos returns cost function weight for quadratic position error term More... | |
virtual double | getWeightVel () const =0 |
getWeightVel returns cost function weight for quadratic velocity error term More... | |
virtual double | getWeightAcc () const =0 |
getWeightAcc returns cost function weight for quadratic acceleration term More... | |
virtual double | getWeightJerk () const =0 |
getWeightJerk returns cost function weight for quadratic jerk term More... | |
virtual double | getWeightEndPos () const =0 |
getWeightEndPos returns cost function weight for quadratic position error term at end point More... | |
virtual double | getWeightEndVel () const =0 |
getWeightEndVel returns cost function weight for quadratic velocity error term at end point More... | |
virtual double | getWeightEndAcc () const =0 |
getWeightEndAcc returns cost function weight for quadratic acceleration term at end point More... | |
virtual double | getSlackPos () const =0 |
getSlackPos returns maximum slack of soft-constraints for position More... | |
virtual double | getSlackVel () const =0 |
getSlackVel returns maximum slack of soft-constraints for velocity More... | |
virtual double | getSlackAcc () const =0 |
getSlackAcc returns maximum slack of soft-constraints for acceleration More... | |
virtual double | getAccLB () const =0 |
getAccLB returns longitudinal acceleration lower bound More... | |
virtual double | getAccUB () const =0 |
getAccUB returns longitudinal acceleration upper bound More... | |
virtual double | getAccUBSlow () const =0 |
getAccUBSlow returns acceleration upper bound at low speeds More... | |
virtual double | getVAccUBSlow () const =0 |
getVAccUBSlow returns speed up to which slow speed acceleration is used More... | |
virtual double | getComfortAccLB () const =0 |
getAccLB returns longitudinal acceleration lower bound More... | |
virtual double | getComfortAccUB () const =0 |
getAccUB returns longitudinal acceleration upper bound More... | |
virtual double | getJerkLB () const =0 |
getJerkLB returns longitudinal jerk lower bound More... | |
virtual double | getJerkUB () const =0 |
getJerkLB returns longitudinal jerk upper bound More... | |
virtual double | getAccLatUB () const =0 |
getAccLatUB returns the absolute lateral acceleration bound which has to be maintained by reducing speed More... | |
virtual double | getAccLatUB_minVelocity () const =0 |
getAccLatUB_minVelocity returns the minimum velocity, which is always feasible despite getAccLatUB More... | |
virtual double | getConstraintClearancePos () const =0 |
getConstraintClearancePos returns the longitudinal offset of the reference from the position constraints More... | |
virtual double | getConstraintClearanceVel () const =0 |
getConstraintClearanceVel returns the offset of the reference from the velocity constraints More... | |
virtual double | getMinWidthStop () const =0 |
getMinWidthStop returns the minimum lane width, below/at which vehicle stops: Should be greater or equal to ap_vehicle::bodyWidth + 2*ap_lateral_planner_::HardSafetyDistanceToLaneBoundary More... | |
virtual double | getMinWidthSlow () const =0 |
getMinWidthSlow returns the minimum lane width, below/at which vehicle moves slowly: Should be greater or queal to minWidthStop More... | |
virtual double | getMinWidthSlowSpeed () const =0 |
getMinWidthSlowSpeed returns the slow speed to be applied, if lane width equals minWidthSlow: Should be greater than 0 More... | |
virtual double | getMinWidthFast () const =0 |
getMinWidthFast returns the minimum lane width, below/at which vehicle moves fast: Should be greater or queal to minWidthSlow More... | |
virtual double | getMinWidthFastSpeed () const =0 |
getMinWidthFastSpeed returns the fast speed to be applied, if lane width equals minWidthFast: Should be greater than minWidthSlowSpeed More... | |
virtual double | getMaxCPUTime () const =0 |
getMaxCPUTime returns the maximum cpu time for one plan computation More... | |
virtual bool | stopAtRedLights_always_before () const =0 |
determin stop mode for red lights: true - always before red light, continue driving after; false - based on deceleration curve More... | |
virtual double | stopAtRedLights_max_connection_length () const =0 |
stopAtRedLights_max_connection_length returns the maximum length for which clearance based on tcd state is considered - after maximum length, vehicle continues. More... | |
virtual double | getStopDistanceToConflictPoint () const =0 |
distance between stop position and conflict point More... | |
abstract class containing parameters related to configuring the longitudinal planner
|
pure virtual |
getAccLatUB returns the absolute lateral acceleration bound which has to be maintained by reducing speed
Implemented in adore::if_ROS::params::PLongitudinalPlanner, and adore::params::APLongitudinalPlannerDummy.
|
pure virtual |
getAccLatUB_minVelocity returns the minimum velocity, which is always feasible despite getAccLatUB
Implemented in adore::if_ROS::params::PLongitudinalPlanner, and adore::params::APLongitudinalPlannerDummy.
|
pure virtual |
getAccLB returns longitudinal acceleration lower bound
Implemented in adore::if_ROS::params::PLongitudinalPlanner, and adore::params::APLongitudinalPlannerDummy.
|
pure virtual |
getAccUB returns longitudinal acceleration upper bound
Implemented in adore::if_ROS::params::PLongitudinalPlanner, and adore::params::APLongitudinalPlannerDummy.
|
pure virtual |
getAccUBSlow returns acceleration upper bound at low speeds
Implemented in adore::if_ROS::params::PLongitudinalPlanner.
|
pure virtual |
getAccLB returns longitudinal acceleration lower bound
Implemented in adore::params::APLongitudinalPlannerDummy, and adore::if_ROS::params::PLongitudinalPlanner.
|
pure virtual |
getAccUB returns longitudinal acceleration upper bound
Implemented in adore::params::APLongitudinalPlannerDummy, and adore::if_ROS::params::PLongitudinalPlanner.
|
pure virtual |
getConstraintClearancePos returns the longitudinal offset of the reference from the position constraints
Implemented in adore::if_ROS::params::PLongitudinalPlanner, and adore::params::APLongitudinalPlannerDummy.
|
pure virtual |
getConstraintClearanceVel returns the offset of the reference from the velocity constraints
Implemented in adore::if_ROS::params::PLongitudinalPlanner, and adore::params::APLongitudinalPlannerDummy.
|
pure virtual |
getJerkLB returns longitudinal jerk lower bound
Implemented in adore::if_ROS::params::PLongitudinalPlanner, and adore::params::APLongitudinalPlannerDummy.
|
pure virtual |
getJerkLB returns longitudinal jerk upper bound
Implemented in adore::if_ROS::params::PLongitudinalPlanner, and adore::params::APLongitudinalPlannerDummy.
|
pure virtual |
getMaxCPUTime returns the maximum cpu time for one plan computation
Implemented in adore::if_ROS::params::PLongitudinalPlanner, and adore::params::APLongitudinalPlannerDummy.
|
pure virtual |
getMinWidthFast returns the minimum lane width, below/at which vehicle moves fast: Should be greater or queal to minWidthSlow
Implemented in adore::if_ROS::params::PLongitudinalPlanner.
|
pure virtual |
getMinWidthFastSpeed returns the fast speed to be applied, if lane width equals minWidthFast: Should be greater than minWidthSlowSpeed
Implemented in adore::if_ROS::params::PLongitudinalPlanner.
|
pure virtual |
getMinWidthSlow returns the minimum lane width, below/at which vehicle moves slowly: Should be greater or queal to minWidthStop
Implemented in adore::if_ROS::params::PLongitudinalPlanner.
|
pure virtual |
getMinWidthSlowSpeed returns the slow speed to be applied, if lane width equals minWidthSlow: Should be greater than 0
Implemented in adore::if_ROS::params::PLongitudinalPlanner.
|
pure virtual |
getMinWidthStop returns the minimum lane width, below/at which vehicle stops: Should be greater or equal to ap_vehicle::bodyWidth + 2*ap_lateral_planner_::HardSafetyDistanceToLaneBoundary
Implemented in adore::if_ROS::params::PLongitudinalPlanner.
|
pure virtual |
getSlackAcc returns maximum slack of soft-constraints for acceleration
Implemented in adore::if_ROS::params::PLongitudinalPlanner, and adore::params::APLongitudinalPlannerDummy.
|
pure virtual |
getSlackPos returns maximum slack of soft-constraints for position
Implemented in adore::if_ROS::params::PLongitudinalPlanner, and adore::params::APLongitudinalPlannerDummy.
|
pure virtual |
getSlackVel returns maximum slack of soft-constraints for velocity
Implemented in adore::if_ROS::params::PLongitudinalPlanner, and adore::params::APLongitudinalPlannerDummy.
|
pure virtual |
distance between stop position and conflict point
Implemented in adore::if_ROS::params::PLongitudinalPlanner, and adore::params::APLongitudinalPlannerDummy.
|
pure virtual |
getVAccUBSlow returns speed up to which slow speed acceleration is used
Implemented in adore::if_ROS::params::PLongitudinalPlanner.
|
pure virtual |
getWeightAcc returns cost function weight for quadratic acceleration term
Implemented in adore::if_ROS::params::PLongitudinalPlanner, and adore::params::APLongitudinalPlannerDummy.
|
pure virtual |
getWeightEndAcc returns cost function weight for quadratic acceleration term at end point
Implemented in adore::if_ROS::params::PLongitudinalPlanner, and adore::params::APLongitudinalPlannerDummy.
|
pure virtual |
getWeightEndPos returns cost function weight for quadratic position error term at end point
Implemented in adore::if_ROS::params::PLongitudinalPlanner, and adore::params::APLongitudinalPlannerDummy.
|
pure virtual |
getWeightEndVel returns cost function weight for quadratic velocity error term at end point
Implemented in adore::if_ROS::params::PLongitudinalPlanner, and adore::params::APLongitudinalPlannerDummy.
|
pure virtual |
getWeightJerk returns cost function weight for quadratic jerk term
Implemented in adore::if_ROS::params::PLongitudinalPlanner, and adore::params::APLongitudinalPlannerDummy.
|
pure virtual |
getWeightPos returns cost function weight for quadratic position error term
Implemented in adore::if_ROS::params::PLongitudinalPlanner, and adore::params::APLongitudinalPlannerDummy.
|
pure virtual |
getWeightVel returns cost function weight for quadratic velocity error term
Implemented in adore::if_ROS::params::PLongitudinalPlanner, and adore::params::APLongitudinalPlannerDummy.
|
pure virtual |
determin stop mode for red lights: true - always before red light, continue driving after; false - based on deceleration curve
Implemented in adore::if_ROS::params::PLongitudinalPlanner.
|
pure virtual |
stopAtRedLights_max_connection_length returns the maximum length for which clearance based on tcd state is considered - after maximum length, vehicle continues.
Implemented in adore::if_ROS::params::PLongitudinalPlanner.