Skip to content

Commit 50a110a

Browse files
authored
perf(map_based_prediction): remove unncessary withinRoadLanelet() (#8403)
Signed-off-by: Mamoru Sobue <mamoru.sobue@tier4.jp>
1 parent 278304e commit 50a110a

File tree

1 file changed

+0
-2
lines changed

1 file changed

+0
-2
lines changed

perception/autoware_map_based_prediction/src/map_based_prediction_node.cpp

-2
Original file line numberDiff line numberDiff line change
@@ -662,15 +662,13 @@ ObjectClassification::_label_type changeLabelForPrediction(
662662
}
663663

664664
case ObjectClassification::PEDESTRIAN: {
665-
const bool within_road_lanelet = withinRoadLanelet(object, lanelet_map_ptr_, true);
666665
const float max_velocity_for_human_mps =
667666
autoware::universe_utils::kmph2mps(25.0); // Max human being motion speed is 25km/h
668667
const double abs_speed = std::hypot(
669668
object.kinematics.twist_with_covariance.twist.linear.x,
670669
object.kinematics.twist_with_covariance.twist.linear.y);
671670
const bool high_speed_object = abs_speed > max_velocity_for_human_mps;
672671
// fast, human-like object: like segway
673-
if (within_road_lanelet && high_speed_object) return label; // currently do nothing
674672
// return ObjectClassification::MOTORCYCLE;
675673
if (high_speed_object) return label; // currently do nothing
676674
// fast human outside road lanelet will move like unknown object

0 commit comments

Comments
 (0)