Skip to content

Commit

Permalink
modified CMD of dockerfiles
Browse files Browse the repository at this point in the history
  • Loading branch information
KalanaRatnayake committed Jul 19, 2024
1 parent ef2ff14 commit 3c6a50d
Show file tree
Hide file tree
Showing 5 changed files with 65 additions and 44 deletions.
20 changes: 10 additions & 10 deletions docker/Dockerfile
Original file line number Diff line number Diff line change
Expand Up @@ -101,16 +101,16 @@ CMD ros2 launch boxmot_ros docker.launch.py yolo_model:=$YOLO_MODEL \
input_rgb_topic:=$INPUT_RGB_TOPIC \
input_depth_topic:=$INPUT_DEPTH_TOPIC \
subscribe_depth:=$SUBSCRIBE_DEPTH \
publish_annotated_image:=$PUBLISH_ANNOTATED_IMAGE \
annotated_topic:=$YOLO_ANNOTATED_TOPIC \
detailed_topic:=$YOLO_DETAILED_TOPIC \
threshold:=$YOLO_THRESHOLD \
device:=$YOLO_DEVICE \
yolo_publish_annotated_image:=$YOLO_PUBLISH_ANNOTATED_IMAGE \
yolo_annotated_topic:=$YOLO_ANNOTATED_TOPIC \
yolo_detailed_topic:=$YOLO_DETAILED_TOPIC \
yolo_threshold:=$YOLO_THRESHOLD \
yolo_device:=$YOLO_DEVICE \
tracking_model:=$TRACKING_MODEL \
reid_model:=$REID_MODEL \
input_topic:=$INPUT_TOPIC \
publish_annotated_image:=$PUBLISH_ANNOTATED_IMAGE \
annotated_topic:=$BOXMOT_ANNOTATED_TOPIC \
detailed_topic:=$BOXMOT_DETAILED_TOPIC \
threshold:=$BOXMOT_THRESHOLD \
device:=$BOXMOT_DEVICE
boxmot_publish_annotated_image:=$BOXMOT_PUBLISH_ANNOTATED_IMAGE \
boxmot_annotated_topic:=$BOXMOT_ANNOTATED_TOPIC \
boxmot_detailed_topic:=$BOXMOT_DETAILED_TOPIC \
boxmot_threshold:=$BOXMOT_THRESHOLD \
boxmot_device:=$BOXMOT_DEVICE
21 changes: 10 additions & 11 deletions docker/Dockerfile.jetson-nano
Original file line number Diff line number Diff line change
Expand Up @@ -81,17 +81,16 @@ CMD ros2 launch boxmot_ros docker.launch.py yolo_model:=$YOLO_MODEL \
input_rgb_topic:=$INPUT_RGB_TOPIC \
input_depth_topic:=$INPUT_DEPTH_TOPIC \
subscribe_depth:=$SUBSCRIBE_DEPTH \
publish_annotated_image:=$PUBLISH_ANNOTATED_IMAGE \
annotated_topic:=$YOLO_ANNOTATED_TOPIC \
detailed_topic:=$YOLO_DETAILED_TOPIC \
threshold:=$YOLO_THRESHOLD \
device:=$YOLO_DEVICE \
yolo_publish_annotated_image:=$YOLO_PUBLISH_ANNOTATED_IMAGE \
yolo_annotated_topic:=$YOLO_ANNOTATED_TOPIC \
yolo_detailed_topic:=$YOLO_DETAILED_TOPIC \
yolo_threshold:=$YOLO_THRESHOLD \
yolo_device:=$YOLO_DEVICE \
tracking_model:=$TRACKING_MODEL \
reid_model:=$REID_MODEL \
input_topic:=$INPUT_TOPIC \
publish_annotated_image:=$PUBLISH_ANNOTATED_IMAGE \
annotated_topic:=$BOXMOT_ANNOTATED_TOPIC \
detailed_topic:=$BOXMOT_DETAILED_TOPIC \
threshold:=$BOXMOT_THRESHOLD \
device:=$BOXMOT_DEVICE

boxmot_publish_annotated_image:=$BOXMOT_PUBLISH_ANNOTATED_IMAGE \
boxmot_annotated_topic:=$BOXMOT_ANNOTATED_TOPIC \
boxmot_detailed_topic:=$BOXMOT_DETAILED_TOPIC \
boxmot_threshold:=$BOXMOT_THRESHOLD \
boxmot_device:=$BOXMOT_DEVICE
4 changes: 2 additions & 2 deletions docker/compose.amd64.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@ services:
- TRACKING_MODEL=deepocsort
- REID_MODEL=osnet_x0_25_msmt17.pt
- INPUT_TOPIC=/yolo_ros/detection_result
- PUBLISH_ANNOTATED_IMAGE=True
- BOXMOT_PUBLISH_ANNOTATED_IMAGE=True
- BOXMOT_ANNOTATED_TOPIC=/boxmot_ros/annotated_image
- BOXMOT_DETAILED_TOPIC=/boxmot_ros/tracking_result
- BOXMOT_THRESHOLD=0.25
Expand All @@ -15,7 +15,7 @@ services:
- INPUT_RGB_TOPIC=/camera/color/image_raw
- INPUT_DEPTH_TOPIC=/camera/depth/points
- SUBSCRIBE_DEPTH=True
- PUBLISH_ANNOTATED_IMAGE=True
- YOLO_PUBLISH_ANNOTATED_IMAGE=True
- YOLO_ANNOTATED_TOPIC=/yolo_ros/annotated_image
- YOLO_DETAILED_TOPIC=/yolo_ros/detection_result
- YOLO_THRESHOLD=0.25
Expand Down
4 changes: 2 additions & 2 deletions docker/compose.jnano.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@ services:
- TRACKING_MODEL=deepocsort
- REID_MODEL=osnet_x0_25_msmt17.pt
- INPUT_TOPIC=/yolo_ros/detection_result
- PUBLISH_ANNOTATED_IMAGE=True
- BOXMOT_PUBLISH_ANNOTATED_IMAGE=True
- BOXMOT_ANNOTATED_TOPIC=/boxmot_ros/annotated_image
- BOXMOT_DETAILED_TOPIC=/boxmot_ros/tracking_result
- BOXMOT_THRESHOLD=0.25
Expand All @@ -15,7 +15,7 @@ services:
- INPUT_RGB_TOPIC=/camera/color/image_raw
- INPUT_DEPTH_TOPIC=/camera/depth/points
- SUBSCRIBE_DEPTH=True
- PUBLISH_ANNOTATED_IMAGE=True
- YOLO_PUBLISH_ANNOTATED_IMAGE=True
- YOLO_ANNOTATED_TOPIC=/yolo_ros/annotated_image
- YOLO_DETAILED_TOPIC=/yolo_ros/detection_result
- YOLO_THRESHOLD=0.25
Expand Down
60 changes: 41 additions & 19 deletions launch/docker.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,39 +3,61 @@
import ament_index_python.packages
import launch_ros.actions
from launch import LaunchDescription
from launch.substitutions import LaunchConfiguration
from launch.actions import DeclareLaunchArgument

import yaml


def generate_launch_description():
yolo_yolo_model_param = DeclareLaunchArgument('yolo_model', default_value="yolov9s.pt")
yolo_input_rgb_topic_param = DeclareLaunchArgument('input_rgb_topic', default_value="/camera/color/image_raw")
yolo_input_depth_topic_param = DeclareLaunchArgument('input_depth_topic', default_value="/camera/depth/points")
yolo_subscribe_depth_param = DeclareLaunchArgument('subscribe_depth', default_value=True)
yolo_publish_annotated_image_param = DeclareLaunchArgument('publish_annotated_image', default_value=True)
yolo_annotated_topic_param = DeclareLaunchArgument('annotated_topic', default_value="/yolo_ros/annotated_image")
yolo_detailed_topic_param = DeclareLaunchArgument('detailed_topic', default_value="/yolo_ros/detection_result")
yolo_threshold_param = DeclareLaunchArgument('threshold', default_value=0.25)
yolo_device_param = DeclareLaunchArgument('device', default_value="0")
yolo_yolo_model_param = DeclareLaunchArgument('yolo_model', default_value="yolov9s.pt")
yolo_input_rgb_topic_param = DeclareLaunchArgument('input_rgb_topic', default_value="/camera/color/image_raw")
yolo_input_depth_topic_param = DeclareLaunchArgument('input_depth_topic', default_value="/camera/depth/points")
yolo_subscribe_depth_param = DeclareLaunchArgument('subscribe_depth', default_value=True)
yolo_publish_annotated_image_param = DeclareLaunchArgument('yolo_publish_annotated_image', default_value=True)
yolo_annotated_topic_param = DeclareLaunchArgument('yolo_annotated_topic', default_value="/yolo_ros/annotated_image")
yolo_detailed_topic_param = DeclareLaunchArgument('yolo_detailed_topic', default_value="/yolo_ros/detection_result")
yolo_threshold_param = DeclareLaunchArgument('yolo_threshold', default_value=0.25)
yolo_device_param = DeclareLaunchArgument('yolo_device', default_value="0")

boxmot_yolo_model_param = DeclareLaunchArgument('tracking_model', default_value="deepocsort")
boxmot_input_rgb_topic_param = DeclareLaunchArgument('reid_model', default_value="osnet_x0_25_msmt17.pt")
boxmot_input_depth_topic_param = DeclareLaunchArgument('input_topic', default_value="/yolo_ros/detection_result")
boxmot_publish_annotated_image_param = DeclareLaunchArgument('publish_annotated_image', default_value=True)
boxmot_annotated_topic_param = DeclareLaunchArgument('annotated_topic', default_value="/boxmot_ros/annotated_image")
boxmot_detailed_topic_param = DeclareLaunchArgument('detailed_topic', default_value="/boxmot_ros/tracking_result")
boxmot_threshold_param = DeclareLaunchArgument('threshold', default_value=0.25)
boxmot_device_param = DeclareLaunchArgument('device', default_value="0")
boxmot_yolo_model_param = DeclareLaunchArgument('tracking_model', default_value="deepocsort")
boxmot_input_rgb_topic_param = DeclareLaunchArgument('reid_model', default_value="osnet_x0_25_msmt17.pt")
boxmot_input_depth_topic_param = DeclareLaunchArgument('input_topic', default_value="/yolo_ros/detection_result")
boxmot_publish_annotated_image_param = DeclareLaunchArgument('boxmot_publish_annotated_image', default_value=True)
boxmot_annotated_topic_param = DeclareLaunchArgument('boxmot_annotated_topic', default_value="/boxmot_ros/annotated_image")
boxmot_detailed_topic_param = DeclareLaunchArgument('boxmot_detailed_topic', default_value="/boxmot_ros/tracking_result")
boxmot_threshold_param = DeclareLaunchArgument('boxmot_threshold', default_value=0.25)
boxmot_device_param = DeclareLaunchArgument('boxmot_device', default_value="0")

yolo_ros_node = launch_ros.actions.Node(package='yolo_ros',
executable='yolo_ros',
output='both'
output='both',
parameters=[{
'yolo_model': LaunchConfiguration('yolo_model'),
'input_rgb_topic': LaunchConfiguration('input_rgb_topic'),
'input_depth_topic': LaunchConfiguration('input_depth_topic'),
'subscribe_depth': LaunchConfiguration('subscribe_depth'),
'publish_annotated_image': LaunchConfiguration('yolo_publish_annotated_image'),
'annotated_topic': LaunchConfiguration('yolo_annotated_topic'),
'detailed_topic': LaunchConfiguration('yolo_detailed_topic'),
'threshold': LaunchConfiguration('yolo_threshold'),
'device': LaunchConfiguration('yolo_device'),
}]
)

boxmot_ros_node = launch_ros.actions.Node(package='boxmot_ros',
executable='boxmot_ros',
output='both'
output='both',
parameters=[{
'tracking_model': LaunchConfiguration('tracking_model'),
'reid_model': LaunchConfiguration('reid_model'),
'input_topic': LaunchConfiguration('input_topic'),
'publish_annotated_image': LaunchConfiguration('boxmot_publish_annotated_image'),
'annotated_topic': LaunchConfiguration('boxmot_annotated_topic'),
'detailed_topic': LaunchConfiguration('boxmot_detailed_topic'),
'threshold': LaunchConfiguration('boxmot_threshold'),
'device': LaunchConfiguration('boxmot_device')
}]
)

ld = LaunchDescription()
Expand Down

0 comments on commit 3c6a50d

Please sign in to comment.