38 static const std::string name =
prefix_ +
"roadbased_prediction_duration";
46 static const std::string name =
prefix_ +
"roadbased_expected_acc_ub";
54 static const std::string name =
prefix_ +
"roadbased_expected_acc_ub_delay";
62 static const std::string name =
prefix_ +
"roadbased_expected_acc_lb";
70 static const std::string name =
prefix_ +
"roadbased_expected_vel_ub";
78 static const std::string name =
prefix_ +
"roadbased_worstcase_acc_ub";
86 static const std::string name =
prefix_ +
"roadbased_worstcase_acc_ub_delay";
94 static const std::string name =
prefix_ +
"roadbased_worstcase_acc_lb";
102 static const std::string name =
prefix_ +
"roadbased_worstcase_vel_ub";
109 double value =
M_PI*0.25;
110 static const std::string name =
prefix_ +
"roadbased_heading_deviation_ub";
118 static const std::string name =
prefix_ +
"roadbased_lat_precision";
126 static const std::string name =
prefix_ +
"roadbased_lat_error";
134 static const std::string name =
prefix_ +
"roadbased_lon_error";
142 static const std::string name =
prefix_ +
"roadbased_time_headway";
150 static const std::string name =
prefix_ +
"roadbased_time_leeway";
158 static const std::string name =
prefix_ +
"offroad_prediction_duration";
166 static const std::string name =
prefix_ +
"offroad_expected_acc_ub";
174 static const std::string name =
prefix_ +
"offroad_expected_acc_lb";
182 static const std::string name =
prefix_ +
"offroad_expected_vel_ub";
190 static const std::string name =
prefix_ +
"offroad_worstcase_acc_ub";
198 static const std::string name =
prefix_ +
"offroad_worstcase_acc_ub_delay";
205 double value = -10.0;
206 static const std::string name =
prefix_ +
"offroad_worstcase_acc_lb";
214 static const std::string name =
prefix_ +
"offroad_worstcase_vel_ub";
222 static const std::string name =
prefix_ +
"offroad_lat_precision";
230 static const std::string name =
prefix_ +
"offroad_lat_error";
238 static const std::string name =
prefix_ +
"offroad_lon_error";
246 static const std::string name =
prefix_ +
"offroad_time_headway";
254 static const std::string name =
prefix_ +
"offroad_time_leeway";
262 static const std::string name =
prefix_ +
"area_of_interest_shrink";
270 static const std::string name =
prefix_ +
"area_of_effect_shrink";
278 static const std::string name =
prefix_ +
"worstcase_filter_precedence";
286 static const std::string name =
prefix_ +
"worstcase_filter_tcd";
294 static const std::string name =
prefix_ +
"setbased_prediction_strategy";
302 static const std::string name =
prefix_ +
"prediction_width_ub";
310 static const std::string name =
prefix_ +
"prediction_width_lb";
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_prediction.h:28
virtual double get_roadbased_heading_deviation_ub() const override
maximum difference between object and road heading for object to be matchable to road
Definition: p_prediction.h:107
virtual bool get_worstcase_filter_tcd() const
filtering of tcd for worstcase maneuvers:
Definition: p_prediction.h:283
virtual double get_roadbased_expected_vel_ub() const override
maximum velocity for normal behavior for objects that can be matched to road
Definition: p_prediction.h:67
virtual double get_roadbased_expected_acc_lb() const override
minimum acceleration for normal behavior for objects that can be matched to road
Definition: p_prediction.h:59
virtual double get_roadbased_worstcase_acc_lb() const override
minimum acceleration for worst-case for objects that can be matched to road
Definition: p_prediction.h:91
virtual double get_offroad_expected_acc_lb() const override
minimum acceleration for normal behavior for objects that can not be matched to road
Definition: p_prediction.h:171
virtual double get_area_of_effect_shrink() const override
filtering out all static objects not inside area of effect
Definition: p_prediction.h:267
virtual double get_offroad_time_leeway() const override
time buffer behind object (object predicted to leave a location given seconds later)
Definition: p_prediction.h:251
virtual int get_setbased_prediction_strategy() const
returns prediction strategy: 0 width of object, 1 width of road, 2 width of object-> width of road
Definition: p_prediction.h:291
virtual double get_roadbased_expected_acc_ub_delay() const override
delay after which expected_acc_ub is applied
Definition: p_prediction.h:51
virtual double get_roadbased_lon_error() const override
assumed maximum longitudinal detection error for objects that can be matched to road (buffer zone)
Definition: p_prediction.h:131
virtual double get_offroad_prediction_duration() const override
prediction duration for objects that can not be matched to road
Definition: p_prediction.h:155
virtual double get_offroad_lat_precision() const override
precision of object shape approximation in lateral direction for objects that can not be matched to r...
Definition: p_prediction.h:219
virtual double get_offroad_lon_error() const override
assumed maximum longitudinal detection error for objects that can not be matched to road
Definition: p_prediction.h:235
virtual bool get_worstcase_filter_precedence() const
filtering of precedence rules for worstcase maneuvers:
Definition: p_prediction.h:275
virtual double get_offroad_worstcase_acc_ub_delay() const override
delay after which worstcase_acc_ub is applied
Definition: p_prediction.h:195
virtual double get_offroad_expected_vel_ub() const override
maximum velocity for normal behavior for objects that can not be matched to road
Definition: p_prediction.h:179
virtual double get_offroad_time_headway() const override
time buffer ahead of an object (objrect predicted to arrive given seconds earlier at a location)
Definition: p_prediction.h:243
virtual double get_offroad_worstcase_acc_ub() const override
maximum acceleration for worst-case behavior for objects that can not be matched to road
Definition: p_prediction.h:187
virtual double get_offroad_lat_error() const override
assumed maximum lateral detection error for objects that can not be matched to road
Definition: p_prediction.h:227
virtual double get_roadbased_time_leeway() const override
time buffer behind object (object predicted to leave a location given seconds later)
Definition: p_prediction.h:147
virtual double get_roadbased_prediction_duration() const override
prediction duration for objects that can be matched to road
Definition: p_prediction.h:35
virtual double get_prediction_width_lb() const
returns the minimum width for a prediction
Definition: p_prediction.h:307
virtual double get_roadbased_worstcase_vel_ub() const override
maximum velocity for worst-case for objects that can be matched to road
Definition: p_prediction.h:99
virtual double get_roadbased_worstcase_acc_ub_delay() const override
delay after which worstcase_acc_ub is applied
Definition: p_prediction.h:83
virtual double get_prediction_width_ub() const
returns maximum width for a prediction
Definition: p_prediction.h:299
virtual double get_roadbased_worstcase_acc_ub() const override
maximum acceleration for worst-case behavior for objects that can be matched to road
Definition: p_prediction.h:75
virtual double get_roadbased_time_headway() const override
time buffer ahead of an object (objrect predicted to arrive given seconds earlier at a location)
Definition: p_prediction.h:139
virtual double get_offroad_worstcase_acc_lb() const override
minimum acceleration for worst-case behavior for objects that can not be matched to road
Definition: p_prediction.h:203
virtual double get_offroad_expected_acc_ub() const override
maximum acceleration for normal behavior for objects that can not be matched to road
Definition: p_prediction.h:163
virtual double get_area_of_interest_shrink() const override
distinction between clutter and static traffic objects: how far into road has object to extend to be ...
Definition: p_prediction.h:259
PPrediction(ros::NodeHandle n, std::string prefix)
Definition: p_prediction.h:30
virtual double get_roadbased_lat_precision() const override
precision of object shape approximation in lateral direction for objects that can be matched to road
Definition: p_prediction.h:115
virtual double get_roadbased_lat_error() const override
assumed maximum lateral detection error for objects that can be matched to road (buffer zone)
Definition: p_prediction.h:123
virtual double get_offroad_worstcase_vel_ub() const override
maximum velocity for worst-case behavior for objects that can not be matched to road
Definition: p_prediction.h:211
virtual double get_roadbased_expected_acc_ub() const override
maximum acceleration for normal behavior for objects that can be matched to road
Definition: p_prediction.h:43
parameter interface for parameters related to prediction
Definition: ap_prediction.h:28
Definition: areaofeffectconverter.h:20