|
1 | | -import os |
2 | | -import sys |
| 1 | +# Copyright 2023 Ar-Ray-code |
| 2 | +# |
| 3 | +# Licensed under the Apache License, Version 2.0 (the "License"); |
| 4 | +# you may not use this file except in compliance with the License. |
| 5 | +# You may obtain a copy of the License at |
| 6 | +# |
| 7 | +# http://www.apache.org/licenses/LICENSE-2.0 |
| 8 | +# |
| 9 | +# Unless required by applicable law or agreed to in writing, software |
| 10 | +# distributed under the License is distributed on an "AS IS" BASIS, |
| 11 | +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 12 | +# See the License for the specific language governing permissions and |
| 13 | +# limitations under the License. |
| 14 | + |
| 15 | + |
3 | 16 | import launch |
4 | | -import launch_ros.actions |
5 | 17 | from launch.actions import DeclareLaunchArgument |
6 | 18 | from launch.substitutions import LaunchConfiguration |
7 | 19 | from launch_ros.actions import ComposableNodeContainer |
|
10 | 22 | def generate_launch_description(): |
11 | 23 | launch_args = [ |
12 | 24 | DeclareLaunchArgument( |
13 | | - "video_device", |
14 | | - default_value="/dev/video0", |
15 | | - description="input video source" |
| 25 | + 'video_device', |
| 26 | + default_value='/dev/video0', |
| 27 | + description='input video source' |
16 | 28 | ), |
17 | 29 | DeclareLaunchArgument( |
18 | | - "model_path", |
19 | | - default_value="./src/YOLOX-ROS/weights/onnx/yolox_tiny.onnx", |
20 | | - description="yolox model path." |
| 30 | + 'model_path', |
| 31 | + default_value='./src/YOLOX-ROS/weights/onnx/yolox_tiny.onnx', |
| 32 | + description='yolox model path.' |
21 | 33 | ), |
22 | 34 | DeclareLaunchArgument( |
23 | | - "p6", |
24 | | - default_value="false", |
25 | | - description="with p6." |
| 35 | + 'p6', |
| 36 | + default_value='false', |
| 37 | + description='with p6.' |
26 | 38 | ), |
27 | 39 | DeclareLaunchArgument( |
28 | | - "class_labels_path", |
29 | | - default_value="''", |
30 | | - description="if use custom model, set class name labels. " |
| 40 | + 'class_labels_path', |
| 41 | + default_value='', |
| 42 | + description='if use custom model, set class name labels. ' |
31 | 43 | ), |
32 | 44 | DeclareLaunchArgument( |
33 | | - "num_classes", |
34 | | - default_value="80", |
35 | | - description="num classes." |
| 45 | + 'num_classes', |
| 46 | + default_value='80', |
| 47 | + description='num classes.' |
36 | 48 | ), |
37 | 49 | DeclareLaunchArgument( |
38 | | - "model_version", |
39 | | - default_value="0.1.1rc0", |
40 | | - description="yolox model version." |
| 50 | + 'model_version', |
| 51 | + default_value='0.1.1rc0', |
| 52 | + description='yolox model version.' |
41 | 53 | ), |
42 | 54 | DeclareLaunchArgument( |
43 | | - "onnxruntime/use_cuda", |
44 | | - default_value="true", |
45 | | - description="onnxruntime use cuda." |
| 55 | + 'onnxruntime/use_cuda', |
| 56 | + default_value='true', |
| 57 | + description='onnxruntime use cuda.' |
46 | 58 | ), |
47 | 59 | DeclareLaunchArgument( |
48 | | - "onnxruntime/device_id", |
49 | | - default_value="0", |
50 | | - description="onnxruntime gpu device id." |
| 60 | + 'onnxruntime/device_id', |
| 61 | + default_value='0', |
| 62 | + description='onnxruntime gpu device id.' |
51 | 63 | ), |
52 | 64 | DeclareLaunchArgument( |
53 | | - "onnxruntime/use_parallel", |
54 | | - default_value="false", |
55 | | - description="if use_parallel is true, you can set inter_op_num_threads." |
| 65 | + 'onnxruntime/use_parallel', |
| 66 | + default_value='false', |
| 67 | + description='if use_parallel is true, you can set inter_op_num_threads.' |
56 | 68 | ), |
57 | 69 | DeclareLaunchArgument( |
58 | | - "onnxruntime/inter_op_num_threads", |
59 | | - default_value="1", |
60 | | - description="control the number of threads used to parallelize the execution of the graph (across nodes)." |
| 70 | + 'onnxruntime/inter_op_num_threads', |
| 71 | + default_value='1' |
61 | 72 | ), |
62 | 73 | DeclareLaunchArgument( |
63 | | - "onnxruntime/intra_op_num_threads", |
64 | | - default_value="1", |
65 | | - description="ontrols the number of threads to use to run the model." |
| 74 | + 'onnxruntime/intra_op_num_threads', |
| 75 | + default_value='1', |
| 76 | + description='ontrols the number of threads to use to run the model.' |
66 | 77 | ), |
67 | 78 | DeclareLaunchArgument( |
68 | | - "conf", |
69 | | - default_value="0.30", |
70 | | - description="yolox confidence threshold." |
| 79 | + 'conf', |
| 80 | + default_value='0.30', |
| 81 | + description='yolox confidence threshold.' |
71 | 82 | ), |
72 | 83 | DeclareLaunchArgument( |
73 | | - "nms", |
74 | | - default_value="0.45", |
75 | | - description="yolox nms threshold" |
| 84 | + 'nms', |
| 85 | + default_value='0.45', |
| 86 | + description='yolox nms threshold' |
76 | 87 | ), |
77 | 88 | DeclareLaunchArgument( |
78 | | - "imshow_isshow", |
79 | | - default_value="true", |
80 | | - description="" |
| 89 | + 'imshow_isshow', |
| 90 | + default_value='true', |
| 91 | + description='' |
81 | 92 | ), |
82 | 93 | DeclareLaunchArgument( |
83 | | - "src_image_topic_name", |
84 | | - default_value="/image_raw", |
85 | | - description="topic name for source image" |
| 94 | + 'src_image_topic_name', |
| 95 | + default_value='/image_raw', |
| 96 | + description='topic name for source image' |
86 | 97 | ), |
87 | 98 | DeclareLaunchArgument( |
88 | | - "publish_image_topic_name", |
89 | | - default_value="/yolox/image_raw", |
90 | | - description="topic name for publishing image with bounding box drawn" |
| 99 | + 'publish_image_topic_name', |
| 100 | + default_value='/yolox/image_raw', |
| 101 | + description='topic name for publishing image with bounding box drawn' |
91 | 102 | ), |
92 | 103 | DeclareLaunchArgument( |
93 | | - "publish_boundingbox_topic_name", |
94 | | - default_value="/yolox/bounding_boxes", |
95 | | - description="topic name for publishing bounding box message." |
| 104 | + 'publish_boundingbox_topic_name', |
| 105 | + default_value='/yolox/bounding_boxes', |
| 106 | + description='topic name for publishing bounding box message.' |
96 | 107 | ), |
97 | 108 | ] |
98 | 109 | container = ComposableNodeContainer( |
99 | | - name='yolox_container', |
100 | | - namespace='', |
101 | | - package='rclcpp_components', |
102 | | - executable='component_container', |
103 | | - composable_node_descriptions=[ |
104 | | - ComposableNode( |
105 | | - package='v4l2_camera', |
106 | | - plugin='v4l2_camera::V4L2Camera', |
107 | | - name='v4l2_camera', |
108 | | - parameters=[{ |
109 | | - "video_device": LaunchConfiguration("video_device"), |
110 | | - "image_size": [640,480] |
111 | | - }]), |
112 | | - ComposableNode( |
113 | | - package='yolox_ros_cpp', |
114 | | - plugin='yolox_ros_cpp::YoloXNode', |
115 | | - name='yolox_ros_cpp', |
116 | | - parameters=[{ |
117 | | - "model_path": LaunchConfiguration("model_path"), |
118 | | - "p6": LaunchConfiguration("p6"), |
119 | | - "class_labels_path": LaunchConfiguration("class_labels_path"), |
120 | | - "num_classes": LaunchConfiguration("num_classes"), |
121 | | - "model_type": "onnxruntime", |
122 | | - "model_version": LaunchConfiguration("model_version"), |
123 | | - "onnxruntime/use_cuda": LaunchConfiguration("onnxruntime/use_cuda"), |
124 | | - "onnxruntime/device_id": LaunchConfiguration("onnxruntime/device_id"), |
125 | | - "onnxruntime/use_parallel": LaunchConfiguration("onnxruntime/use_parallel"), |
126 | | - "onnxruntime/inter_op_num_threads": LaunchConfiguration("onnxruntime/inter_op_num_threads"), |
127 | | - "onnxruntime/intra_op_num_threads": LaunchConfiguration("onnxruntime/intra_op_num_threads"), |
128 | | - "conf": LaunchConfiguration("conf"), |
129 | | - "nms": LaunchConfiguration("nms"), |
130 | | - "imshow_isshow": LaunchConfiguration("imshow_isshow"), |
131 | | - "src_image_topic_name": LaunchConfiguration("src_image_topic_name"), |
132 | | - "publish_image_topic_name": LaunchConfiguration("publish_image_topic_name"), |
133 | | - "publish_boundingbox_topic_name": LaunchConfiguration("publish_boundingbox_topic_name"), |
134 | | - }], |
135 | | - ), |
136 | | - ], |
137 | | - output='screen', |
138 | | - ) |
139 | | - |
140 | | - rqt = launch_ros.actions.Node( |
141 | | - package="rqt_graph", executable="rqt_graph", |
| 110 | + name='yolox_container', |
| 111 | + namespace='', |
| 112 | + package='rclcpp_components', |
| 113 | + executable='component_container', |
| 114 | + composable_node_descriptions=[ |
| 115 | + ComposableNode( |
| 116 | + package='v4l2_camera', |
| 117 | + plugin='v4l2_camera::V4L2Camera', |
| 118 | + name='v4l2_camera', |
| 119 | + parameters=[{ |
| 120 | + 'video_device': LaunchConfiguration('video_device'), |
| 121 | + 'image_size': [640, 480] |
| 122 | + }]), |
| 123 | + ComposableNode( |
| 124 | + package='yolox_ros_cpp', |
| 125 | + plugin='yolox_ros_cpp::YoloXNode', |
| 126 | + name='yolox_ros_cpp', |
| 127 | + parameters=[{ |
| 128 | + 'model_path': LaunchConfiguration('model_path'), |
| 129 | + 'p6': LaunchConfiguration('p6'), |
| 130 | + 'class_labels_path': LaunchConfiguration('class_labels_path'), |
| 131 | + 'num_classes': LaunchConfiguration('num_classes'), |
| 132 | + 'model_type': 'onnxruntime', |
| 133 | + 'model_version': LaunchConfiguration('model_version'), |
| 134 | + 'onnxruntime/use_cuda': LaunchConfiguration('onnxruntime/use_cuda'), |
| 135 | + 'onnxruntime/device_id': LaunchConfiguration('onnxruntime/device_id'), |
| 136 | + 'onnxruntime/use_parallel': LaunchConfiguration('onnxruntime/use_parallel'), |
| 137 | + 'onnxruntime/inter_op_num_threads': LaunchConfiguration('onnxruntime/inter_op_num_threads'), |
| 138 | + 'onnxruntime/intra_op_num_threads': LaunchConfiguration('onnxruntime/intra_op_num_threads'), |
| 139 | + 'conf': LaunchConfiguration('conf'), |
| 140 | + 'nms': LaunchConfiguration('nms'), |
| 141 | + 'imshow_isshow': LaunchConfiguration('imshow_isshow'), |
| 142 | + 'src_image_topic_name': LaunchConfiguration('src_image_topic_name'), |
| 143 | + 'publish_image_topic_name': LaunchConfiguration('publish_image_topic_name'), |
| 144 | + 'publish_boundingbox_topic_name': LaunchConfiguration('publish_boundingbox_topic_name'), |
| 145 | + }], |
| 146 | + ), |
| 147 | + ], |
| 148 | + output='screen', |
142 | 149 | ) |
143 | 150 |
|
144 | 151 | return launch.LaunchDescription( |
145 | 152 | launch_args + |
146 | 153 | [ |
147 | | - container, |
148 | | - # rqt_graph, |
| 154 | + container |
149 | 155 | ] |
150 | 156 | ) |
0 commit comments