ultralytics_ros
ultralytics_ros copied to clipboard
3D bounding box displaying problem
Branch
noetic-devel
Question
Hello, Thank you for open sourcing your great work. I attempted to reproduce the object detection results using a point cloud (3D object detection). I downloaded the same kitti dataset (2011_09_26_drive_0106_sync) and run the "kitti_tracker_with_cloud.launch". 2D object detection with and without segmentation is fine, and there is no error. However, I could not see any 3D bounding boxes on the point cloud. This is illustrated in the attached screenshots. Could you please let me know what could be a possible solution to this problem? Note: I tried all–yolov8 models (yolov8n-seg. pt, yolov8m-seg.pt, etc.) and also increases voxel_leaf_size, as suggested, but nothing works.
Here's my working configuration:
- Operating System: Ubuntu 20.04
- Hardware: Nvidia Agx_orin
- ROS Version: ROS Noetic
Thank you @imdsafi09 for your report! 👍🏻 I have a few points of concern to mention.
- Your
rqt_graph
includes/predict_with_cloud_node
, which is implemented in the melodic-devel branch. Given that your operating environment is Noetic, you should be using the noetic-devel branch. It's probable that melodic-devel might work well in a Noetic environment, but switching to the correct branch is advisable... - Please confirm if data is flowing correctly by echoing the
/yolo_result
,/detection_cloud
and/detection_marker
. - Make sure the callback function in
tracker_with_cloud_node
is called as expected. Logging in the following way should make this clear:
If the timestamp ofvoid TrackerWithCloudNode::syncCallback(const sensor_msgs::CameraInfo::ConstPtr& camera_info_msg, const sensor_msgs::PointCloud2ConstPtr& cloud_msg, const ultralytics_ros::YoloResultConstPtr& yolo_result_msg) { ROS_INFO("HELLO!!"); ros::Time current_call_time = ros::Time::now(); ... }
/yolo_result
published by thetracker_node
is significantly different from/kitti/camera_color_left/camera_info
or/kitti/velo/pointcloud
, this may preventsyncCallback()
from being called. Consider increasing the queue size to see if this improves the situation:camera_info_sub_.subscribe(nh_, camera_info_topic_, 10); lidar_sub_.subscribe(nh_, lidar_topic_, 10); yolo_result_sub_.subscribe(nh_, yolo_result_topic_, 10); sync_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy>>(1);
Best regards,
Hello @Alpaca-zip Thank you for your feedback. I shifted from Nvidia Agx_orin (ROS-Noetic) to my PC, where I am using ROS-Melodic. After changing the queue size as followed, it is now working properly.
camera_info_sub_.subscribe(nh_, camera_info_topic_, 1); lidar_sub_.subscribe(nh_, lidar_topic_, 1); yolo_result_sub_.subscribe(nh_, yolo_result_topic_, 1); sync_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy>>(100);
However, when I am doing the same changes in noetic branch I am facing the error showing in the screenshot. Could you please let me know what could be the possible solution.
I have two additional questions.
- The 3D bounding boxes appear to have a fixed orientation regardless of the 2D bounding box shape. Is there a solution to have a 3D bounding box oreintation similar to the 2D one? Is it possible to solve this issue by using "Oriented Bounding Boxes Object Detection [https://docs.ultralytics.com/tasks/obb/]?
- I have an Ouster lidar (Os-128), which provides signal images (mono-16). I am able to subscribe to the lidar signal images for yolov8 and publish 2D bounding boxes. However, lidar is not a standard camera, and thus the camera info topic is missing. Therefore, I want to determine what could be a possible solution to this problem.
Best regards,