Skip to content

Commit

Permalink
fix(autoware_lidar_centerpoint): convert object's velocity to follow …
Browse files Browse the repository at this point in the history
…its definition (autowarefoundation#8980)

* fix: convert object's velocity to follow its definition in box3DToDetectedObject function

Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp>

* Update perception/autoware_lidar_centerpoint/lib/ros_utils.cpp

Co-authored-by: Kenzo Lobos Tsunekawa <kenzo.lobos@tier4.jp>

---------

Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp>
Co-authored-by: Kenzo Lobos Tsunekawa <kenzo.lobos@tier4.jp>
  • Loading branch information
technolojin and knzo25 committed Sep 30, 2024
1 parent 706fd97 commit 1442d18
Showing 1 changed file with 4 additions and 2 deletions.
6 changes: 4 additions & 2 deletions perception/autoware_lidar_centerpoint/lib/ros_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,8 +68,10 @@ void box3DToDetectedObject(
float vel_x = box3d.vel_x;
float vel_y = box3d.vel_y;
geometry_msgs::msg::Twist twist;
twist.linear.x = std::sqrt(std::pow(vel_x, 2) + std::pow(vel_y, 2));
twist.angular.z = 2 * (std::atan2(vel_y, vel_x) - yaw);
twist.linear.x = std::cos(yaw) * vel_x + std::sin(yaw) * vel_y;
twist.linear.y = -std::sin(yaw) * vel_x + std::cos(yaw) * vel_y;
twist.angular.z = 0; // angular velocity is not supported

obj.kinematics.twist_with_covariance.twist = twist;
obj.kinematics.has_twist = has_twist;
if (has_variance) {
Expand Down

0 comments on commit 1442d18

Please sign in to comment.