31 :
ROSParam(n,prefix +
"longitudinal_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";
118 static const std::string name =
prefix_ +
"acc_lb";
126 static const std::string name =
prefix_ +
"acc_ub";
135 static const std::string name =
prefix_ +
"acc_ub_slow";
144 static const std::string name =
prefix_ +
"v_acc_ub_slow";
153 static const std::string name =
prefix_ +
"comf_acc_lb";
162 static const std::string name =
prefix_ +
"comf_acc_ub";
170 double value = -100.0;
171 static const std::string name =
prefix_ +
"jerk_lb";
178 double value = 100.0;
179 static const std::string name =
prefix_ +
"jerk_ub";
187 static const std::string name =
prefix_ +
"acc_lat_ub";
195 static const std::string name =
prefix_ +
"acc_lat_ub_min_velocity";
203 static const std::string name =
prefix_ +
"constraint_clearance_pos";
211 static const std::string name =
prefix_ +
"constraint_clearance_vel";
221 static const std::string name =
prefix_ +
"min_width_stop";
230 static const std::string name =
prefix_ +
"min_width_slow";
239 static const std::string name =
prefix_ +
"min_width_slow_speed";
248 static const std::string name =
prefix_ +
"min_width_fast";
256 double value = 40.0/3.6;
257 static const std::string name =
prefix_ +
"min_width_fast_speed";
267 static const std::string name =
prefix_ +
"max_cpu_time";
276 static const std::string name =
prefix_ +
"stopAtRedLights_always_before";
284 static const std::string name =
prefix_ +
"stopAtRedLights_max_connection_length";
294 static const std::string name =
prefix_ +
"stop_distance_to_conflict_point";
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_longitudinal_planner.h:28
virtual double getWeightEndAcc() const override
getWeightEndAcc returns cost function weight for quadratic acceleration term at end point
Definition: p_longitudinal_planner.h:83
virtual double getMinWidthStop() const override
getMinWidthStop returns the minimum lane width, below/at which vehicle stops: Should be greater or eq...
Definition: p_longitudinal_planner.h:218
virtual double getJerkLB() const override
getJerkLB returns longitudinal jerk lower bound
Definition: p_longitudinal_planner.h:168
virtual double getComfortAccLB() const override
getAccLB returns longitudinal acceleration lower bound
Definition: p_longitudinal_planner.h:150
virtual double getAccUBSlow() const override
getAccUBSlow returns acceleration upper bound at low speeds
Definition: p_longitudinal_planner.h:132
virtual double getMinWidthSlowSpeed() const override
getMinWidthSlowSpeed returns the slow speed to be applied, if lane width equals minWidthSlow: Should ...
Definition: p_longitudinal_planner.h:236
virtual double getJerkUB() const override
getJerkLB returns longitudinal jerk upper bound
Definition: p_longitudinal_planner.h:176
virtual double getMinWidthFast() const override
getMinWidthFast returns the minimum lane width, below/at which vehicle moves fast: Should be greater ...
Definition: p_longitudinal_planner.h:245
virtual double getConstraintClearanceVel() const override
getConstraintClearanceVel returns the offset of the reference from the velocity constraints
Definition: p_longitudinal_planner.h:208
virtual double getComfortAccUB() const override
getAccUB returns longitudinal acceleration upper bound
Definition: p_longitudinal_planner.h:159
virtual double getWeightEndPos() const override
getWeightEndPos returns cost function weight for quadratic position error term at end point
Definition: p_longitudinal_planner.h:67
virtual double getWeightJerk() const override
getWeightJerk returns cost function weight for quadratic jerk term
Definition: p_longitudinal_planner.h:59
virtual double getStopDistanceToConflictPoint() const override
distance between stop position and conflict point
Definition: p_longitudinal_planner.h:291
virtual double getWeightAcc() const override
getWeightAcc returns cost function weight for quadratic acceleration term
Definition: p_longitudinal_planner.h:51
virtual double getMinWidthFastSpeed() const override
getMinWidthFastSpeed returns the fast speed to be applied, if lane width equals minWidthFast: Should ...
Definition: p_longitudinal_planner.h:254
virtual double getWeightPos() const override
getWeightPos returns cost function weight for quadratic position error term
Definition: p_longitudinal_planner.h:35
virtual double getAccUB() const override
getAccUB returns longitudinal acceleration upper bound
Definition: p_longitudinal_planner.h:123
virtual double getMinWidthSlow() const override
getMinWidthSlow returns the minimum lane width, below/at which vehicle moves slowly: Should be greate...
Definition: p_longitudinal_planner.h:227
PLongitudinalPlanner(ros::NodeHandle n, std::string prefix)
Definition: p_longitudinal_planner.h:30
virtual bool stopAtRedLights_always_before() const override
determin stop mode for red lights: true - always before red light, continue driving after; false - ba...
Definition: p_longitudinal_planner.h:273
virtual double getAccLatUB_minVelocity() const override
getAccLatUB_minVelocity returns the minimum velocity, which is always feasible despite getAccLatUB
Definition: p_longitudinal_planner.h:192
virtual double getVAccUBSlow() const override
getVAccUBSlow returns speed up to which slow speed acceleration is used
Definition: p_longitudinal_planner.h:141
virtual double getWeightVel() const override
getWeightVel returns cost function weight for quadratic velocity error term
Definition: p_longitudinal_planner.h:43
virtual double getMaxCPUTime() const override
getMaxCPUTime returns the maximum cpu time for one plan computation
Definition: p_longitudinal_planner.h:264
virtual double getSlackVel() const override
getSlackVel returns maximum slack of soft-constraints for velocity
Definition: p_longitudinal_planner.h:99
virtual double getConstraintClearancePos() const override
getConstraintClearancePos returns the longitudinal offset of the reference from the position constrai...
Definition: p_longitudinal_planner.h:200
virtual double getSlackAcc() const override
getSlackAcc returns maximum slack of soft-constraints for acceleration
Definition: p_longitudinal_planner.h:107
virtual double getAccLatUB() const override
getAccLatUB returns the absolute lateral acceleration bound which has to be maintained by reducing sp...
Definition: p_longitudinal_planner.h:184
virtual double getWeightEndVel() const override
getWeightEndVel returns cost function weight for quadratic velocity error term at end point
Definition: p_longitudinal_planner.h:75
virtual double getSlackPos() const override
getSlackPos returns maximum slack of soft-constraints for position
Definition: p_longitudinal_planner.h:91
virtual double getAccLB() const override
getAccLB returns longitudinal acceleration lower bound
Definition: p_longitudinal_planner.h:115
virtual double stopAtRedLights_max_connection_length() const override
stopAtRedLights_max_connection_length returns the maximum length for which clearance based on tcd sta...
Definition: p_longitudinal_planner.h:281
abstract class containing parameters related to configuring the longitudinal planner
Definition: ap_longitudinal_planner.h:26
Definition: areaofeffectconverter.h:20