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): merge velocity base on target object coordinate system #6457

Merged
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
68 changes: 45 additions & 23 deletions perception/tracking_object_merger/src/utils/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -324,43 +324,61 @@
// copy main object at first
output_kinematics = main_obj.kinematics;
auto sub_obj_ = sub_obj;
// do not merge reverse direction objects
// do not merge if motion direction is different
if (!objectsHaveSameMotionDirections(main_obj, sub_obj)) {
return output_kinematics;
} else if (objectsYawIsReverted(main_obj, sub_obj)) {
// revert velocity (revert pose is not necessary because it is not used in tracking)
sub_obj_.kinematics.twist_with_covariance.twist.linear.x *= -1.0;
sub_obj_.kinematics.twist_with_covariance.twist.linear.y *= -1.0;
}

// currently only merge vx
if (policy == MergePolicy::SKIP) {
return output_kinematics;
} else if (policy == MergePolicy::OVERWRITE) {
output_kinematics.twist_with_covariance.twist.linear.x =
sub_obj_.kinematics.twist_with_covariance.twist.linear.x;
// use main_obj's orientation
// take sub_obj's velocity vector and convert into main_obj's frame, but take only x component
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;

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

View check run for this annotation

Codecov / codecov/patch

perception/tracking_object_merger/src/utils/utils.cpp#L338-L339

Added lines #L338 - L339 were not covered by tests
const auto main_yaw = tf2::getYaw(main_obj.kinematics.pose_with_covariance.pose.orientation);
const auto sub_yaw = tf2::getYaw(sub_obj_.kinematics.pose_with_covariance.pose.orientation);
const auto sub_vx_in_main_frame =
sub_vx * std::cos(sub_yaw - main_yaw) + sub_vy * std::sin(sub_yaw - main_yaw);
output_kinematics.twist_with_covariance.twist.linear.x = sub_vx_in_main_frame;

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

View check run for this annotation

Codecov / codecov/patch

perception/tracking_object_merger/src/utils/utils.cpp#L342-L344

Added lines #L342 - L344 were not covered by tests

return output_kinematics;
} else if (policy == MergePolicy::FUSION) {
// use main_obj's orientation
// take main_obj's velocity vector and convert into sub_obj's frame, but take only x component
const auto main_vx = main_obj.kinematics.twist_with_covariance.twist.linear.x;
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;

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

View check run for this annotation

Codecov / codecov/patch

perception/tracking_object_merger/src/utils/utils.cpp#L352

Added line #L352 was not covered by tests
const auto main_yaw = tf2::getYaw(main_obj.kinematics.pose_with_covariance.pose.orientation);
const auto sub_yaw = tf2::getYaw(sub_obj_.kinematics.pose_with_covariance.pose.orientation);
const auto sub_vel_in_main_frame_x =
sub_vx * std::cos(sub_yaw - main_yaw) + sub_vy * std::sin(sub_yaw - main_yaw);

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

View check run for this annotation

Codecov / codecov/patch

perception/tracking_object_merger/src/utils/utils.cpp#L355-L356

Added lines #L355 - L356 were not covered by tests
// inverse weight
const auto main_vx_cov = main_obj.kinematics.twist_with_covariance.covariance[0];
const auto sub_vx_cov = sub_obj_.kinematics.twist_with_covariance.covariance[0];
const auto sub_vy_cov = sub_obj_.kinematics.twist_with_covariance.covariance[7];
const auto sub_vel_cov_in_main_frame_x =
sub_vx_cov * std::cos(sub_yaw - main_yaw) * std::cos(sub_yaw - main_yaw) +
sub_vy_cov * std::sin(sub_yaw - main_yaw) * std::sin(sub_yaw - main_yaw);

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

View check run for this annotation

Codecov / codecov/patch

perception/tracking_object_merger/src/utils/utils.cpp#L360-L363

Added lines #L360 - L363 were not covered by tests
double main_vx_weight, sub_vx_weight;
if (main_vx_cov == 0.0) {
main_vx_weight = 1.0 * 1e6;
} else {
main_vx_weight = 1.0 / main_vx_cov;
}
if (sub_vx_cov == 0.0) {
if (sub_vel_cov_in_main_frame_x == 0.0) {

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

View check run for this annotation

Codecov / codecov/patch

perception/tracking_object_merger/src/utils/utils.cpp#L370

Added line #L370 was not covered by tests
sub_vx_weight = 1.0 * 1e6;
} else {
sub_vx_weight = 1.0 / sub_vx_cov;
sub_vx_weight = 1.0 / sub_vel_cov_in_main_frame_x;

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

View check run for this annotation

Codecov / codecov/patch

perception/tracking_object_merger/src/utils/utils.cpp#L373

Added line #L373 was not covered by tests
}
// merge with covariance

// merge velocity with covariance
output_kinematics.twist_with_covariance.twist.linear.x =
(main_vx * main_vx_weight + sub_vx * sub_vx_weight) / (main_vx_weight + sub_vx_weight);
(main_vx * main_vx_weight + sub_vel_in_main_frame_x * sub_vx_weight) /
(main_vx_weight + sub_vx_weight);

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

View check run for this annotation

Codecov / codecov/patch

perception/tracking_object_merger/src/utils/utils.cpp#L378-L379

Added lines #L378 - L379 were not covered by tests
output_kinematics.twist_with_covariance.covariance[0] = 1.0 / (main_vx_weight + sub_vx_weight);

return output_kinematics;
} else {
std::cerr << "unknown merge policy in objectKinematicsMerger function." << std::endl;
Expand Down Expand Up @@ -453,21 +471,25 @@

void updateExceptVelocity(TrackedObject & main_obj, const TrackedObject & sub_obj)
{
// do not update if motion direction is different
if (!objectsHaveSameMotionDirections(main_obj, sub_obj)) {
// do not update velocity
return;
} else if (objectsYawIsReverted(main_obj, sub_obj)) {
// revert velocity (revert pose is not necessary because it is not used in tracking)
const auto vx_temp = sub_obj.kinematics.twist_with_covariance.twist.linear.x;
main_obj = sub_obj;
main_obj.kinematics.twist_with_covariance.twist.linear.x = -vx_temp;
return;
} else {
// update velocity
const auto vx_temp = sub_obj.kinematics.twist_with_covariance.twist.linear.x;
main_obj = sub_obj;
main_obj.kinematics.twist_with_covariance.twist.linear.x = vx_temp;
}
// take main_obj's velocity vector and convert into sub_obj's frame
// use sub_obj's orientation, but take only x component
const auto main_vx = main_obj.kinematics.twist_with_covariance.twist.linear.x;
const auto main_vy = main_obj.kinematics.twist_with_covariance.twist.linear.y;

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

View check run for this annotation

Codecov / codecov/patch

perception/tracking_object_merger/src/utils/utils.cpp#L480-L481

Added lines #L480 - L481 were not covered by tests
const auto main_yaw = tf2::getYaw(main_obj.kinematics.pose_with_covariance.pose.orientation);
const auto sub_yaw = tf2::getYaw(sub_obj.kinematics.pose_with_covariance.pose.orientation);
const auto main_vx_in_sub_frame =
main_vx * std::cos(main_yaw - sub_yaw) + main_vy * std::sin(main_yaw - sub_yaw);

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

View check run for this annotation

Codecov / codecov/patch

perception/tracking_object_merger/src/utils/utils.cpp#L484-L485

Added lines #L484 - L485 were not covered by tests

// copy sub object to fused object
main_obj = sub_obj;

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

View check run for this annotation

Codecov / codecov/patch

perception/tracking_object_merger/src/utils/utils.cpp#L488

Added line #L488 was not covered by tests
// recover main object's velocity
main_obj.kinematics.twist_with_covariance.twist.linear.x = main_vx_in_sub_frame;

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

View check run for this annotation

Codecov / codecov/patch

perception/tracking_object_merger/src/utils/utils.cpp#L490

Added line #L490 was not covered by tests

return;

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

View check run for this annotation

Codecov / codecov/patch

perception/tracking_object_merger/src/utils/utils.cpp#L492

Added line #L492 was not covered by tests
}

void updateOnlyObjectVelocity(TrackedObject & main_obj, const TrackedObject & sub_obj)
Expand Down
Loading