31 :
ROSParam(n,prefix +
"tactical_planner/")
37 static const std::string name =
prefix_ +
"global_speed_limit";
44 static const std::string name =
prefix_ +
"reset_radius";
51 static const std::string name =
prefix_ +
"acc_lat_ub";
58 static const std::string name =
prefix_ +
"acc_lat_ub_min_vel";
65 static const std::string name =
prefix_ +
"acc_lon_ub";
72 static const std::string name =
prefix_ +
"acc_lon_lb";
79 static const std::string name =
prefix_ +
"front_time_gap";
86 static const std::string name =
prefix_ +
"rear_time_gap";
93 static const std::string name =
prefix_ +
"front_s_gap";
100 static const std::string name =
prefix_ +
"lower_bound_lf_front_s_gap";
107 static const std::string name =
prefix_ +
"rear_s_gap";
114 static const std::string name =
prefix_ +
"chase_reference_offset";
121 static const std::string name =
prefix_ +
"lead_reference_offset";
128 static const std::string name =
prefix_ +
"front_reference_offset";
135 static const std::string name =
prefix_ +
"gap_alignment";
142 static const std::string name =
prefix_ +
"assumed_nominal_acceleration_minimum";
149 static const std::string name =
prefix_ +
"max_navcost_loss";
156 static const std::string name =
prefix_ +
"enforce_monotonous_navigation_cost";
163 static const std::string name =
prefix_ +
"preferred_lc_by_manual_indicator_timeout";
170 static const std::string name =
prefix_ +
"lane_view_reset_velocity";
177 static const std::string name =
prefix_ +
"lanechange_suppression_timeout";
184 static const std::string name =
prefix_ +
"collision_detection_front_buffer_space";
191 static const std::string name =
prefix_ +
"collision_detection_lateral_precision";
198 static const std::string name =
prefix_ +
"collision_detection_lateral_error";
205 static const std::string name =
prefix_ +
"collision_detection_longitudinal_error";
212 static const std::string name =
prefix_ +
"nominal_swath_acceleration_error";
220 static const std::string name =
prefix_ +
"coercion_prevention_strategy";
227 static const std::string name =
prefix_ +
"indicator_lookahead";
234 static const std::string name =
prefix_ +
"horizon_stop_reference_distance";
241 static const std::string name =
prefix_ +
"terminate_after_first_stop_threshold_speed";
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_tactical_planner.h:28
virtual double getTimeoutForPreferredLCAfterManuallySetIndicator() const override
Definition: p_tactical_planner.h:160
virtual double getLeadReferenceOffset() const override
Definition: p_tactical_planner.h:118
virtual double getFrontTimeGap() const override
Definition: p_tactical_planner.h:76
PTacticalPlanner(ros::NodeHandle n, std::string prefix)
Definition: p_tactical_planner.h:30
virtual double getAccLatUB_minVelocity() const override
Definition: p_tactical_planner.h:55
virtual double getRearTimeGap() const override
Definition: p_tactical_planner.h:83
virtual double getCollisionDetectionFrontBufferSpace() const override
Definition: p_tactical_planner.h:181
virtual double getLowerBoundFrontSGapForLF() const override
Definition: p_tactical_planner.h:97
virtual double getAccLonUB() const override
Definition: p_tactical_planner.h:62
virtual double getAccLatUB() const override
Definition: p_tactical_planner.h:48
virtual double getAccLonLB() const override
Definition: p_tactical_planner.h:69
virtual double getTimeoutForLangechangeSuppression() const override
Definition: p_tactical_planner.h:174
virtual double getRearSGap() const override
Definition: p_tactical_planner.h:104
virtual double getGlobalSpeedLimit() const override
Definition: p_tactical_planner.h:34
virtual double getHorizonStopReferenceDistance() const override
Definition: p_tactical_planner.h:231
virtual double getChaseReferenceOffset() const override
Definition: p_tactical_planner.h:111
virtual double getCollisionDetectionLongitudinalError() const override
Definition: p_tactical_planner.h:202
virtual double getIndicatorLookahead() const override
Definition: p_tactical_planner.h:224
virtual double getTerminateAfterFirstStopThresholdSpeed() const override
Definition: p_tactical_planner.h:238
virtual double getCollisionDetectionLateralError() const override
Definition: p_tactical_planner.h:195
virtual double getCollisionDetectionLateralPrecision() const override
Definition: p_tactical_planner.h:188
virtual double getMaxNavcostLoss() const override
Definition: p_tactical_planner.h:146
virtual double getLVResetVelocity() const override
Definition: p_tactical_planner.h:167
virtual double getResetRadius() const override
Definition: p_tactical_planner.h:41
virtual double getGapAlignment() const override
Definition: p_tactical_planner.h:132
virtual double getFrontSGap() const override
Definition: p_tactical_planner.h:90
virtual int getCoercionPreventionStrategy() const override
getCoercionPreventionStrategy returns 0 switched off, 1 objective function, 2 constraint
Definition: p_tactical_planner.h:217
virtual double getFrontReferenceOffset() const override
Definition: p_tactical_planner.h:125
virtual double getAssumedNominalAccelerationMinimum() const override
Definition: p_tactical_planner.h:139
virtual bool getEnforceMonotonousNavigationCost() const override
Definition: p_tactical_planner.h:153
virtual double getNominalSwathAccelerationError() const override
Definition: p_tactical_planner.h:209
abstract classs containing parameters to configure aspects and constraints of the tactical planner
Definition: ap_tactical_planner.h:25
Definition: areaofeffectconverter.h:20