Skip to content

Commit

Permalink
feat(autoware_lidar _ransfusion): fix 3d bounding box orientation (#9052
Browse files Browse the repository at this point in the history
)

* fix bbox orientation

Signed-off-by: Samrat Thapa <[email protected]>

* revert newline changes

Signed-off-by: Samrat Thapa <[email protected]>

* change kernel

Signed-off-by: Samrat Thapa <[email protected]>

---------

Signed-off-by: Samrat Thapa <[email protected]>
Co-authored-by: Amadeusz Szymko <[email protected]>
  • Loading branch information
SamratThapa120 and amadeuszsz authored Oct 8, 2024
1 parent 88e2ae1 commit 43d7bbf
Show file tree
Hide file tree
Showing 2 changed files with 3 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -83,8 +83,8 @@ __global__ void generateBoxes3D_kernel(
det_boxes3d[point_idx].y =
box_output[point_idx + num_proposals] * num_point_values * voxel_size_y + min_y_range;
det_boxes3d[point_idx].z = box_output[point_idx + 2 * num_proposals];
det_boxes3d[point_idx].width = expf(box_output[point_idx + 3 * num_proposals]);
det_boxes3d[point_idx].length = expf(box_output[point_idx + 4 * num_proposals]);
det_boxes3d[point_idx].length = expf(box_output[point_idx + 3 * num_proposals]);
det_boxes3d[point_idx].width = expf(box_output[point_idx + 4 * num_proposals]);
det_boxes3d[point_idx].height = expf(box_output[point_idx + 5 * num_proposals]);
det_boxes3d[point_idx].yaw =
atan2f(dir_cls_output[point_idx], dir_cls_output[point_idx + num_proposals]);
Expand Down
4 changes: 1 addition & 3 deletions perception/autoware_lidar_transfusion/lib/ros_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,12 +48,10 @@ void box3DToDetectedObject(
obj.classification.emplace_back(classification);

// pose and shape
// mmdet3d yaw format to ros yaw format
float yaw = box3d.yaw + autoware::universe_utils::pi / 2;
obj.kinematics.pose_with_covariance.pose.position =
autoware::universe_utils::createPoint(box3d.x, box3d.y, box3d.z);
obj.kinematics.pose_with_covariance.pose.orientation =
autoware::universe_utils::createQuaternionFromYaw(yaw);
autoware::universe_utils::createQuaternionFromYaw(box3d.yaw);
obj.shape.type = autoware_perception_msgs::msg::Shape::BOUNDING_BOX;
obj.shape.dimensions =
autoware::universe_utils::createTranslation(box3d.length, box3d.width, box3d.height);
Expand Down

0 comments on commit 43d7bbf

Please sign in to comment.