Skip to content

Commit c180222

Browse files
committed
feat: change label conversion threshold for pedestrian and bicycle in prediction
Signed-off-by: yoshiri <yoshiyoshidetteiu@gmail.com>
1 parent d6aa2c7 commit c180222

File tree

1 file changed

+4
-4
lines changed

1 file changed

+4
-4
lines changed

perception/map_based_prediction/src/map_based_prediction_node.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -606,7 +606,7 @@ ObjectClassification::_label_type changeLabelForPrediction(
606606
// constraints
607607
const bool within_road_lanelet = withinRoadLanelet(object, lanelet_map_ptr_, true);
608608
const float high_speed_threshold =
609-
tier4_autoware_utils::kmph2mps(25.0); // High speed bicycle 25 km/h
609+
tier4_autoware_utils::kmph2mps(9.0); // For lv4 special tuning. High speed bicycle 9 km/h
610610
// calc abs speed from x and y velocity
611611
const double abs_speed = std::hypot(
612612
object.kinematics.twist_with_covariance.twist.linear.x,
@@ -624,14 +624,14 @@ ObjectClassification::_label_type changeLabelForPrediction(
624624
case ObjectClassification::PEDESTRIAN: {
625625
const bool within_road_lanelet = withinRoadLanelet(object, lanelet_map_ptr_, true);
626626
const float max_velocity_for_human_mps =
627-
tier4_autoware_utils::kmph2mps(25.0); // Max human being motion speed is 25km/h
627+
tier4_autoware_utils::kmph2mps(9.0); // Max human being motion speed is 25km/h
628628
const double abs_speed = std::hypot(
629629
object.kinematics.twist_with_covariance.twist.linear.x,
630630
object.kinematics.twist_with_covariance.twist.linear.y);
631631
const bool high_speed_object = abs_speed > max_velocity_for_human_mps;
632632
// fast, human-like object: like segway
633-
if (within_road_lanelet && high_speed_object) return label; // currently do nothing
634-
// return ObjectClassification::MOTORCYCLE;
633+
if (within_road_lanelet && high_speed_object) //return label; // currently do nothing
634+
return ObjectClassification::MOTORCYCLE;
635635
if (high_speed_object) return label; // currently do nothing
636636
// fast human outside road lanelet will move like unknown object
637637
// return ObjectClassification::UNKNOWN;

0 commit comments

Comments
 (0)