@@ -606,7 +606,7 @@ ObjectClassification::_label_type changeLabelForPrediction(
606
606
// constraints
607
607
const bool within_road_lanelet = withinRoadLanelet (object, lanelet_map_ptr_, true );
608
608
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
610
610
// calc abs speed from x and y velocity
611
611
const double abs_speed = std::hypot (
612
612
object.kinematics .twist_with_covariance .twist .linear .x ,
@@ -624,14 +624,14 @@ ObjectClassification::_label_type changeLabelForPrediction(
624
624
case ObjectClassification::PEDESTRIAN: {
625
625
const bool within_road_lanelet = withinRoadLanelet (object, lanelet_map_ptr_, true );
626
626
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
628
628
const double abs_speed = std::hypot (
629
629
object.kinematics .twist_with_covariance .twist .linear .x ,
630
630
object.kinematics .twist_with_covariance .twist .linear .y );
631
631
const bool high_speed_object = abs_speed > max_velocity_for_human_mps;
632
632
// 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;
635
635
if (high_speed_object) return label; // currently do nothing
636
636
// fast human outside road lanelet will move like unknown object
637
637
// return ObjectClassification::UNKNOWN;
0 commit comments