31 :
ROSParam(n,prefix +
"lateral_planner/")
38 static const std::string name =
prefix_ +
"weight_pos";
46 static const std::string name =
prefix_ +
"weight_vel";
54 static const std::string name =
prefix_ +
"weight_acc";
62 static const std::string name =
prefix_ +
"weight_jerk";
70 static const std::string name =
prefix_ +
"weight_end_pos";
78 static const std::string name =
prefix_ +
"weight_end_vel";
86 static const std::string name =
prefix_ +
"weight_end_acc";
94 static const std::string name =
prefix_ +
"slack_pos";
102 static const std::string name =
prefix_ +
"slack_vel";
110 static const std::string name =
prefix_ +
"slack_acc";
117 double value = -10.0;
118 static const std::string name =
prefix_ +
"acc_lb";
126 static const std::string name =
prefix_ +
"acc_ub";
133 double value = -100.0;
134 static const std::string name =
prefix_ +
"jerk_lb";
141 double value = 100.0;
142 static const std::string name =
prefix_ +
"jerk_ub";
150 static const std::string name =
prefix_ +
"curvature_ub";
157 double value = -0.14;
158 static const std::string name =
prefix_ +
"curvature_lb";
166 static const std::string name =
prefix_ +
"relative_heading_ub";
174 static const std::string name =
prefix_ +
"relative_heading_lb";
182 static const std::string name =
prefix_ +
"merge_constraint_delay";
191 static const std::string name =
prefix_ +
"hard_safety_distance_to_lane_boundary";
200 static const std::string name =
prefix_ +
"soft_safety_distance_to_lane_boundary";
209 static const std::string name =
prefix_ +
"minimum_lateral_control_space";
218 static const std::string name =
prefix_ +
"max_cpu_time";
226 static const std::string name =
prefix_ +
"lateral_grid_scale";
Definition: ros_com_patterns.h:179
std::string prefix_
Definition: ros_com_patterns.h:181
void get(const std::string &name, T &result) const
Definition: ros_com_patterns.h:186
Definition: p_lateral_planner.h:28
virtual double getJerkLB() const override
getJerkLB returns lateral jerk lower bound
Definition: p_lateral_planner.h:131
virtual double getHardSafetyDistanceToLaneBoundary() const override
getHardSafetyDistanceToLaneBoundary returns the minimum distance between lane boundary and vehicle si...
Definition: p_lateral_planner.h:188
PLateralPlanner(ros::NodeHandle n, std::string prefix)
Definition: p_lateral_planner.h:30
virtual double getMinimumLateralControlSpace() const override
getMinimumLateralControlSpace returns the minimum desired lateral control space: If vehicle has more ...
Definition: p_lateral_planner.h:206
virtual double getMaxCPUTime() const override
getMaxCPUTime returns the maximum cpu time for one plan computation
Definition: p_lateral_planner.h:215
virtual double getWeightAcc() const override
getWeightAcc returns cost function weight for quadratic acceleration term
Definition: p_lateral_planner.h:51
virtual double getLateralGridScale() const override
getLateralGridScale returns the size of a grid step d for lateral variations of a maneuver: maneuver ...
Definition: p_lateral_planner.h:223
virtual double getCurvatureUB() const override
getCurvatureUB returns maximum curvature of path (relevant at low speeds)
Definition: p_lateral_planner.h:147
virtual double getAccLB() const override
getAccLB returns lateral acceleration lower bound
Definition: p_lateral_planner.h:115
virtual double getMergeConstraintDelay() const override
getMergeConstraintDelay returns a time-delay after which lateral position constraints are activated,...
Definition: p_lateral_planner.h:179
virtual double getWeightEndVel() const override
getWeightEndVel returns cost function weight for quadratic velocity error term at end point
Definition: p_lateral_planner.h:75
virtual double getWeightEndPos() const override
getWeightEndPos returns cost function weight for quadratic position error term at end point
Definition: p_lateral_planner.h:67
virtual double getRelativeHeadingLB() const override
getRelativeHeadingLB returns lower bound on heading deviation from current lane's coordinate system
Definition: p_lateral_planner.h:171
virtual double getWeightVel() const override
getWeightVel returns cost function weight for quadratic velocity error term
Definition: p_lateral_planner.h:43
virtual double getJerkUB() const override
getJerkLB returns lateral jerk upper bound
Definition: p_lateral_planner.h:139
virtual double getSoftSafetyDistanceToLaneBoundary() const override
getSoftSafetyDistanceToLaneBoundary returns the minimum distance between lane boundary and vehicle si...
Definition: p_lateral_planner.h:197
virtual double getWeightJerk() const override
getWeightJerk returns cost function weight for quadratic jerk term
Definition: p_lateral_planner.h:59
virtual double getSlackPos() const override
getSlackPos returns maximum slack of soft-constraints for position
Definition: p_lateral_planner.h:91
virtual double getSlackAcc() const override
getSlackAcc returns maximum slack of soft-constraints for acceleration
Definition: p_lateral_planner.h:107
virtual double getWeightPos() const override
getWeightPos returns cost function weight for quadratic position error term
Definition: p_lateral_planner.h:35
virtual double getWeightEndAcc() const override
getWeightEndAcc returns cost function weight for quadratic acceleration term at end point
Definition: p_lateral_planner.h:83
virtual double getCurvatureLB() const override
getCurvatureLB returns minimum curvature of path (relevant at low speeds)
Definition: p_lateral_planner.h:155
virtual double getAccUB() const override
getAccUB returns lateral acceleration upper bound
Definition: p_lateral_planner.h:123
virtual double getRelativeHeadingUB() const override
getRelativeHeadingUB returns upper bound on heading deviation from current lane's coordinate system
Definition: p_lateral_planner.h:163
virtual double getSlackVel() const override
getSlackVel returns maximum slack of soft-constraints for velocity
Definition: p_lateral_planner.h:99
abstract class containing parameters related to configuring the lateral planner
Definition: ap_lateral_planner.h:26
Definition: areaofeffectconverter.h:20