Skip to content

Commit

Permalink
minor fixes
Browse files Browse the repository at this point in the history
  • Loading branch information
mgonzs13 committed Oct 27, 2023
1 parent d068b83 commit 9df7207
Show file tree
Hide file tree
Showing 2 changed files with 19 additions and 17 deletions.
34 changes: 17 additions & 17 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -23,12 +23,12 @@ $ ros2 launch yolov8_bringup yolov8.launch.py

#### Parameters

- model: YOLOv8 model (default: yolov8m.pt)
- tracker: tracker file (default: bytetrack.yaml)
- device: GPU/CUDA (default: cuda:0)
- enable: wether to start YOLOv8 enabled (default: True)
- threshold: detection threshold (default: 0.5)
- input_image_topic: camera topic of RGB images (default: /camera/rgb/image_raw)
- **model**: YOLOv8 model (default: yolov8m.pt)
- **tracker**: tracker file (default: bytetrack.yaml)
- **device**: GPU/CUDA (default: cuda:0)
- **enable**: wether to start YOLOv8 enabled (default: True)
- **threshold**: detection threshold (default: 0.5)
- **input_image_topic**: camera topic of RGB images (default: /camera/rgb/image_raw)

### YOLOv8 3D

Expand All @@ -38,17 +38,17 @@ $ ros2 launch yolov8_bringup yolov8_3d.launch.py

#### Parameters

- model: YOLOv8 model (default: yolov8m.pt)
- tracker: tracker file (default: bytetrack.yaml)
- device: GPU/CUDA (default: cuda:0)
- enable: wether to start YOLOv8 enabled (default: True)
- threshold: detection threshold (default: 0.5)
- input_image_topic: camera topic of RGB images (default: /camera/rgb/image_raw)
- input_depth_topic: camera topic of depth images (default: /camera/depth/image_raw)
- input_depth_info_topic: camera topic for info data (default: /camera/depth/camera_info)
- depth_image_units_divisor: divisor to convert the depth image into metres (default: 1000)
- target_frame: frame to transform the 3D boxes (default: base_link)
- maximum_detection_threshold: maximum detection threshold in the z axis (default: 0.3)
- **model**: YOLOv8 model (default: yolov8m.pt)
- **tracker**: tracker file (default: bytetrack.yaml)
- **device**: GPU/CUDA (default: cuda:0)
- **enable**: wether to start YOLOv8 enabled (default: True)
- **threshold**: detection threshold (default: 0.5)
- **input_image_topic**: camera topic of RGB images (default: /camera/rgb/image_raw)
- **input_depth_topic**: camera topic of depth images (default: /camera/depth/image_raw)
- **input_depth_info_topic**: camera topic for info data (default: /camera/depth/camera_info)
- **depth_image_units_divisor**: divisor to convert the depth image into metres (default: 1000)
- **target_frame**: frame to transform the 3D boxes (default: base_link)
- **maximum_detection_threshold**: maximum detection threshold in the z axis (default: 0.3)

## Demos

Expand Down
2 changes: 2 additions & 0 deletions yolov8_ros/yolov8_ros/detect_3d_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -162,6 +162,8 @@ def convert_bb_to_3d(
roi_threshold = roi[mask_z]
z_min, z_max = np.min(roi_threshold), np.max(roi_threshold)
z = (z_max + z_min) / 2
if z == 0:
return None

# project from image to world space
k = depth_info.k
Expand Down

0 comments on commit 9df7207

Please sign in to comment.