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(tracking_object_merger): enable to association unknown class in tracker merger #6182 #1123

Merged
merged 1 commit into from
Feb 2, 2024
Merged
Show file tree
Hide file tree
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 @@ -3,7 +3,7 @@
lidar-lidar:
can_assign_matrix:
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE,PEDESTRIAN
[0, 0, 0, 0, 0, 0, 0, 0, #UNKNOWN
[1, 0, 0, 0, 0, 0, 0, 0, #UNKNOWN
0, 1, 1, 1, 1, 0, 0, 0, #CAR
0, 1, 1, 1, 1, 0, 0, 0, #TRUCK
0, 1, 1, 1, 1, 0, 0, 0, #BUS
Expand Down Expand Up @@ -59,7 +59,7 @@
lidar-radar:
can_assign_matrix:
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE,PEDESTRIAN
[0, 0, 0, 0, 0, 0, 0, 0, #UNKNOWN
[1, 0, 0, 0, 0, 0, 0, 0, #UNKNOWN
0, 1, 1, 1, 1, 0, 0, 0, #CAR
0, 1, 1, 1, 1, 0, 0, 0, #TRUCK
0, 1, 1, 1, 1, 0, 0, 0, #BUS
Expand Down Expand Up @@ -115,7 +115,7 @@
radar-radar:
can_assign_matrix:
#UNKNOWN, CAR, TRUCK, BUS, TRAILER, MOTORBIKE, BICYCLE,PEDESTRIAN
[0, 0, 0, 0, 0, 0, 0, 0, #UNKNOWN
[1, 0, 0, 0, 0, 0, 0, 0, #UNKNOWN
0, 1, 1, 1, 1, 0, 0, 0, #CAR
0, 1, 1, 1, 1, 0, 0, 0, #TRUCK
0, 1, 1, 1, 1, 0, 0, 0, #BUS
Expand Down
6 changes: 3 additions & 3 deletions perception/tracking_object_merger/src/utils/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -272,11 +272,11 @@
const auto sub_vx = sub_obj.kinematics.twist_with_covariance.twist.linear.x;
const auto sub_vy = sub_obj.kinematics.twist_with_covariance.twist.linear.y;
// calc velocity direction
const auto main_vyaw = std::atan2(main_vy, main_vx);

Check warning on line 275 in perception/tracking_object_merger/src/utils/utils.cpp

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (vyaw)
const auto sub_vyaw = std::atan2(sub_vy, sub_vx);

Check warning on line 276 in perception/tracking_object_merger/src/utils/utils.cpp

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (vyaw)
// get motion yaw angle
const auto main_motion_yaw = main_yaw + main_vyaw;

Check warning on line 278 in perception/tracking_object_merger/src/utils/utils.cpp

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (vyaw)
const auto sub_motion_yaw = sub_yaw + sub_vyaw;

Check warning on line 279 in perception/tracking_object_merger/src/utils/utils.cpp

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (vyaw)
// diff of motion yaw angle
const auto motion_yaw_diff = std::fabs(main_motion_yaw - sub_motion_yaw);
const auto normalized_motion_yaw_diff =
Expand Down Expand Up @@ -484,9 +484,9 @@
{
if (!objectsHaveSameMotionDirections(main_obj, sub_obj)) {
// warning
std::cerr << "[object_tracking_merger]: motion direction is different in "
"updateWholeTrackedObject function."
<< std::endl;
// std::cerr << "[object_tracking_merger]: motion direction is different in "
// "updateWholeTrackedObject function."
// << std::endl;
}
main_obj = sub_obj;
}
Expand Down
Loading