Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(map_based_prediction): modiry return label #1000

Open
wants to merge 1 commit into
base: beta/v0.7.3_bicycle_crosswalk_yaw
Choose a base branch
from
Open
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -441,7 +441,7 @@
label == ObjectClassification::MOTORCYCLE || label == ObjectClassification::BICYCLE) {
// if object is within road lanelet and satisfies yaw constraints
const bool within_road_lanelet = withinRoadLanelet(object, lanelet_map_ptr_, true);
const float high_speed_threshold = 25.0 / 18.0 * 5.0; // High speed bycicle 25 km/h

Check warning on line 444 in perception/map_based_prediction/src/map_based_prediction_node.cpp

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (bycicle)
const bool high_speed_object =
object.kinematics.twist_with_covariance.twist.linear.x > high_speed_threshold;

Expand All @@ -450,9 +450,10 @@
return ObjectClassification::MOTORCYCLE;
} else if (high_speed_object) {
// high speed object outside road lanelet will move like unknown object
return ObjectClassification::UNKNOWN;
// return ObjectClassification::UNKNOWN;
return label;
} else {
return label == ObjectClassification::BICYCLE;
return ObjectClassification::BICYCLE;
}
} else if (label == ObjectClassification::PEDESTRIAN) {
const bool within_road_lanelet = withinRoadLanelet(object, lanelet_map_ptr_, true);
Expand Down
Loading