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

[noetic-devel] support multiple encoding #29

Merged
merged 3 commits into from
Sep 8, 2023
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
14 changes: 6 additions & 8 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ endif()
find_package(catkin REQUIRED COMPONENTS
rospy
roscpp
ros_numpy
cv_bridge
pcl_ros
tf2_ros
std_msgs
Expand All @@ -22,17 +22,17 @@ find_package(catkin REQUIRED COMPONENTS
message_filters
)

find_package(Boost REQUIRED COMPONENTS system)
find_package(Boost REQUIRED)
find_package(OpenCV REQUIRED)
find_package(PCL REQUIRED)

catkin_package(
INCLUDE_DIRS
include
LIBRARIES
${PROJECT_NAME}
CATKIN_DEPENDS
rospy
roscpp
cv_bridge
pcl_ros
tf2_ros
std_msgs
Expand All @@ -43,22 +43,20 @@ catkin_package(
image_geometry
image_transport
message_filters
DEPENDS
PCL
)

include_directories(
include
${catkin_INCLUDE_DIRS}
${Boost_INCLUDE_DIRS}
${PCL_INCLUDE_DIRS}
${OpenCV_INCLUDE_DIRS}
${PCL_INCLUDE_DIRS}
)

add_executable(tracker_with_cloud_node src/tracker_with_cloud_node.cpp)
target_link_libraries(tracker_with_cloud_node
${catkin_LIBRARIES}
${Boost_LIBRARIES}
${PCL_LIBRARIES}
${OpenCV_LIBRARIES}
${PCL_LIBRARIES}
)
2 changes: 1 addition & 1 deletion Dockerfile
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# Use tiryoh/ros-desktop-vnc:melodic as the base image
# Use tiryoh/ros-desktop-vnc:noetic as the base image
FROM tiryoh/ros-desktop-vnc:noetic

# Set Environment Variables
Expand Down
91 changes: 58 additions & 33 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,10 +1,14 @@
# ultralytics_ros [![ROS-noetic Docker Build Check](https://github.com/Alpaca-zip/ultralytics_ros/actions/workflows/noetic-docker-build-check.yml/badge.svg)](https://github.com/Alpaca-zip/ultralytics_ros/actions/workflows/noetic-docker-build-check.yml)
ROS package for real-time object detection using the Ultralytics YOLO, enabling flexible integration with various robotics applications.

<img src="https://github.com/Alpaca-zip/ultralytics_ros/assets/84959376/9da7dbbf-5cc0-41bc-be82-d481abbf552a" width="800px">
<img src="https://github.com/Alpaca-zip/ultralytics_ros/assets/84959376/158e7f0c-a823-4425-908d-1b63c11d6e51" width="800px">
| `tracker_node` | `tracker_with_cloud_node` |
| :------------: | :-----------------------: |
| <img src="https://github.com/Alpaca-zip/ultralytics_ros/assets/84959376/9da7dbbf-5cc0-41bc-be82-d481abbf552a" width="450px"> | <img src="https://github.com/Alpaca-zip/ultralytics_ros/assets/84959376/158e7f0c-a823-4425-908d-1b63c11d6e51" width="450px"> |

## Setup
- The `tracker_node` provides real-time object detection on incoming ROS image messages using the Ultralytics YOLO model.
- The `tracker_with_cloud_node` provides functionality for 3D object detection by integrating 2D detections, LiDAR data, and camera information.

## Setup ⚙
```
$ cd ~/catkin_ws/src
$ git clone -b noetic-devel https://github.com/Alpaca-zip/ultralytics_ros.git
Expand All @@ -13,43 +17,65 @@ $ cd ~/catkin_ws
$ rosdep install -r -y -i --from-paths .
$ catkin build
```
## Usage
### Run tracker_node
## Run 🚀
**`tracker_node`**
```
$ roslaunch ultralytics_ros tracker.launch debug:=true
```
### Run tracker_node & tracker_with_cloud_node
**`tracker_node` & `tracker_with_cloud_node`**
```
$ roslaunch ultralytics_ros tracker_with_cloud.launch debug:=true
```
## `tracker_node`
### Params
- tracker_node
- `yolo_model`: Pre-trained Weights.
For yolov8, you can choose `yolov8n.pt`, `yolov8s.pt`, `yolov8m.pt`, `yolov8l.pt`, `yolov8x.pt`.
See also: https://docs.ultralytics.com/models/
- `image_topic`: Topic name for image. (sensor_msgs/Image)
- `detection_topic`: Topic name for 2D bounding box. (vision_msgs/Detection2DArray)
- `conf_thres`: Confidence threshold below which boxes will be filtered out.
- `iou_thres`: IoU threshold below which boxes will be filtered out during NMS.
- `max_det`: Maximum number of boxes to keep after NMS.
- `tracker`: Tracking algorithms.
- `classes`: List of class indices to consider.
See also: https://github.com/ultralytics/ultralytics/blob/main/ultralytics/datasets/coco128.yaml
- `debug`: If true, run simple viewer.
- `debug_conf`: Whether to plot the detection confidence score.
- `debug_line_width`: Line width of the bounding boxes.
- `debug_font_size`: Font size of the text.
- `debug_labels`: Font to use for the text.
- `debug_font`: Whether to plot the label of bounding boxes.
- `debug_boxes`: Whether to plot the bounding boxes.
- `yolo_model`: Pre-trained Weights.
For yolov8, you can choose `yolov8*.pt`, `yolov8*-seg.pt`, `yolov8*-pose.pt`.

- tracker_with_cloud_node
- `camera_info_topic`: Topic name for camera_info. (sensor_msgs/CameraInfo)
- `lidar_topic`: Topic name for lidar. (sensor_msgs/PointCloud2)
- `detection3d_topic`: Topic name for 3D bounding box. (vision_msgs/Detection3DArray)
- `cluster_tolerance`: Spatial cluster tolerance as a measure in the L2 Euclidean space.
- `min_cluster_size`: Minimum number of points that a cluster needs to contain.
- `max_cluster_size`: Maximum number of points that a cluster needs to contain.
| YOLOv8 | <img src="https://github.com/Alpaca-zip/ultralytics_ros/assets/84959376/08770080-bf20-470b-8269-eee7a7c41acc" width="350px"> |
| :-------------: | :-------------: |
| **YOLOv8-seg** | <img src="https://github.com/Alpaca-zip/ultralytics_ros/assets/84959376/7bb6650c-769d-41c1-86f7-39fcbf01bc7c" width="350px"> |
| **YOLOv8-pose** | <img src="https://github.com/Alpaca-zip/ultralytics_ros/assets/84959376/46d2a5ef-193b-4f83-a0b3-6cc0d5a3756c" width="350px"> |

See also: https://docs.ultralytics.com/models/
- `image_topic`: Topic name for image.
- `detection_topic`: Topic name for 2D bounding box.
- `conf_thres`: Confidence threshold below which boxes will be filtered out.
- `iou_thres`: IoU threshold below which boxes will be filtered out during NMS.
- `max_det`: Maximum number of boxes to keep after NMS.
- `tracker`: Tracking algorithms.
- `classes`: List of class indices to consider.
See also: https://github.com/ultralytics/ultralytics/blob/main/ultralytics/datasets/coco128.yaml
- `debug`: If true, run simple viewer.
- `debug_conf`: Whether to plot the detection confidence score.
- `debug_line_width`: Line width of the bounding boxes.
- `debug_font_size`: Font size of the text.
- `debug_labels`: Font to use for the text.
- `debug_font`: Whether to plot the label of bounding boxes.
- `debug_boxes`: Whether to plot the bounding boxes.
### Topics
- Subscribed Topics:
- Image data from `image_topic` parameter. ([sensor_msgs/Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html))
- Published Topics:
- Debug images to `/debug_image` topic. ([sensor_msgs/Image](https://docs.ros.org/en/api/sensor_msgs/html/msg/Image.html))
- Detected objects(2D bounding box) to `detection_topic` parameter. ([vision_msgs/Detection2DArray](http://docs.ros.org/en/melodic/api/vision_msgs/html/msg/Detection2DArray.html))
## `tracker_with_cloud_node`
### Params
- `camera_info_topic`: Topic name for camera info.
- `lidar_topic`: Topic name for lidar.
- `detection2d_topic`: Topic name for 2D bounding box.
- `detection3d_topic`: Topic name for 3D bounding box.
- `cluster_tolerance`: Spatial cluster tolerance as a measure in the L2 Euclidean space.
- `min_cluster_size`: Minimum number of points that a cluster needs to contain.
- `max_cluster_size`: Maximum number of points that a cluster needs to contain.
### Topics
- Subscribed Topics:
- Camera info from `camera_info_topic` parameter. ([sensor_msgs/CameraInfo](https://docs.ros.org/en/api/sensor_msgs/html/msg/CameraInfo.html))
- Lidar data from `lidar_topic` parameter. ([sensor_msgs/PointCloud2](https://docs.ros.org/en/api/sensor_msgs/html/msg/PointCloud2.html))
- Detected objects(2D bounding box) from `detection2d_topic` parameter. ([vision_msgs/Detection2DArray](http://docs.ros.org/en/melodic/api/vision_msgs/html/msg/Detection2DArray.html))
- Published Topics:
- Detected cloud points to `/detection_cloud` topic. ([sensor_msgs/PointCloud2](https://docs.ros.org/en/api/sensor_msgs/html/msg/PointCloud2.html))
- Detected objects(3D bounding box) to `detection3d_topic` parameter. ([vision_msgs/Detection3DArray](http://docs.ros.org/en/lunar/api/vision_msgs/html/msg/Detection3DArray.html))
- Visualization markers to `/detection_marker` topic. ([visualization_msgs/MarkerArray](https://docs.ros.org/en/api/visualization_msgs/html/msg/MarkerArray.html))
## Docker with KITTI datasets 🐳
[![dockeri.co](https://dockerico.blankenship.io/image/alpacazip/ultralytics_ros)](https://hub.docker.com/r/alpacazip/ultralytics_ros)

Expand All @@ -58,7 +84,6 @@ $ roslaunch ultralytics_ros tracker_with_cloud.launch debug:=true
$ docker pull alpacazip/ultralytics_ros:noetic
$ docker run -p 6080:80 --shm-size=512m alpacazip/ultralytics_ros:noetic
```

### Run tracker_node & tracker_with_cloud_node
```
$ roslaunch ultralytics_ros kitti_tracker_with_cloud.launch
Expand Down
2 changes: 1 addition & 1 deletion package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@
<buildtool_depend>catkin</buildtool_depend>
<depend>rospy</depend>
<depend>roscpp</depend>
<depend>ros_numpy</depend>
<depend>cv_bridge</depend>
<depend>pcl_ros</depend>
<depend>tf2_ros</depend>
<depend>std_msgs</depend>
Expand Down
2 changes: 1 addition & 1 deletion requirements.txt
Original file line number Diff line number Diff line change
Expand Up @@ -3,4 +3,4 @@ onnx==1.14.0
urllib3==1.26.11
numpy==1.23.4
opencv-python==4.7.0.72
ultralytics
ultralytics
12 changes: 6 additions & 6 deletions script/tracker_node.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#!/usr/bin/env python3

import ros_numpy
import cv_bridge
import roslib.packages
import rospy
from sensor_msgs.msg import Image
Expand Down Expand Up @@ -36,11 +36,11 @@ def __init__(self):
self.detection_pub = rospy.Publisher(
detection_topic, Detection2DArray, queue_size=1
)
self.bridge = cv_bridge.CvBridge()

def image_callback(self, msg):
header = msg.header
encoding = msg.encoding
numpy_image = ros_numpy.numpify(msg)
numpy_image = self.bridge.imgmsg_to_cv2(msg, desired_encoding="bgr8")
results = self.model.track(
source=numpy_image,
conf=self.conf_thres,
Expand All @@ -51,7 +51,7 @@ def image_callback(self, msg):
verbose=False,
)
self.publish_detection(results, header)
self.publish_debug_image(results, encoding)
self.publish_debug_image(results, "bgr8")

def publish_debug_image(self, results, encoding):
if self.debug and results is not None:
Expand All @@ -63,8 +63,8 @@ def publish_debug_image(self, results, encoding):
labels=self.debug_labels,
boxes=self.debug_boxes,
)
debug_image_msg = ros_numpy.msgify(
Image, plotted_image, encoding=encoding)
debug_image_msg = self.bridge.cv2_to_imgmsg(
plotted_image, encoding="bgr8")
self.image_pub.publish(debug_image_msg)

def publish_detection(self, results, header):
Expand Down
Loading