-
-
Notifications
You must be signed in to change notification settings - Fork 55
/
yolox_openvino.launch.py
126 lines (123 loc) · 4.66 KB
/
yolox_openvino.launch.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
import os
import sys
import launch
import launch_ros.actions
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import ComposableNodeContainer
from launch_ros.descriptions import ComposableNode
def generate_launch_description():
launch_args = [
DeclareLaunchArgument(
"video_device",
default_value="/dev/video0",
description="input video source"
),
DeclareLaunchArgument(
"model_path",
default_value="./install/yolox_ros_cpp/share/yolox_ros_cpp/weights/openvino/yolox_nano.xml",
description="yolox model path."
),
DeclareLaunchArgument(
"p6",
default_value="false",
description="with p6."
),
DeclareLaunchArgument(
"class_labels_path",
default_value="''",
description="if use custom model, set class name labels. "
),
DeclareLaunchArgument(
"num_classes",
default_value="80",
description="num classes."
),
DeclareLaunchArgument(
"model_version",
default_value="0.1.1rc0",
description="yolox model version."
),
DeclareLaunchArgument(
"openvino/device",
default_value="CPU",
description="model device. CPU, GPU, MYRIAD, etc..."
),
DeclareLaunchArgument(
"conf",
default_value="0.30",
description="yolox confidence threshold."
),
DeclareLaunchArgument(
"nms",
default_value="0.45",
description="yolox nms threshold"
),
DeclareLaunchArgument(
"imshow_isshow",
default_value="true",
description=""
),
DeclareLaunchArgument(
"src_image_topic_name",
default_value="/image_raw",
description="topic name for source image"
),
DeclareLaunchArgument(
"publish_image_topic_name",
default_value="/yolox/image_raw",
description="topic name for publishing image with bounding box drawn"
),
DeclareLaunchArgument(
"publish_boundingbox_topic_name",
default_value="/yolox/bounding_boxes",
description="topic name for publishing bounding box message."
),
]
container = ComposableNodeContainer(
name='yolox_container',
namespace='',
package='rclcpp_components',
executable='component_container',
composable_node_descriptions=[
ComposableNode(
package='v4l2_camera',
plugin='v4l2_camera::V4L2Camera',
name='v4l2_camera',
parameters=[{
"video_device": LaunchConfiguration("video_device"),
"image_size": [640,480]
}]),
ComposableNode(
package='yolox_ros_cpp',
plugin='yolox_ros_cpp::YoloXNode',
name='yolox_ros_cpp',
parameters=[{
"model_path": LaunchConfiguration("model_path"),
"p6": LaunchConfiguration("p6"),
"class_labels_path": LaunchConfiguration("class_labels_path"),
"num_classes": LaunchConfiguration("num_classes"),
"model_type": "openvino",
"model_version": LaunchConfiguration("model_version"),
"openvino/device": LaunchConfiguration("openvino/device"),
"conf": LaunchConfiguration("conf"),
"nms": LaunchConfiguration("nms"),
"imshow_isshow": LaunchConfiguration("imshow_isshow"),
"src_image_topic_name": LaunchConfiguration("src_image_topic_name"),
"publish_image_topic_name": LaunchConfiguration("publish_image_topic_name"),
"publish_boundingbox_topic_name": LaunchConfiguration("publish_boundingbox_topic_name"),
}],
),
],
output='screen',
)
rqt = launch_ros.actions.Node(
package="rqt_graph", executable="rqt_graph",
)
return launch.LaunchDescription(
launch_args +
[
container,
# rqt_graph,
]
)