Skip to content

Commit 27b4083

Browse files
committed
update yolox_py
1 parent cca2262 commit 27b4083

13 files changed

+159
-292
lines changed

yolox_ros_py/launch/yolox_lite_tflite_camera.launch.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -37,8 +37,8 @@ def generate_launch_description():
3737
yolox_tflite = launch_ros.actions.Node(
3838
package="yolox_ros_py", executable="yolox_tflite",output="screen",
3939
parameters=[
40-
{"model" : yolox_ros_share_dir+"/model.tflite"},
41-
{"score_th" : 0.4},
40+
{"model_path" : yolox_ros_share_dir+"/model.tflite"},
41+
{"conf" : 0.4},
4242
{"nms_th" : 0.5},
4343
{"input_shape/height" : 192},
4444
{"input_shape/width" : 192}

yolox_ros_py/launch/yolox_nano_onnx_camera.launch.py

Lines changed: 0 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -28,9 +28,6 @@ def generate_launch_description():
2828
yolox_onnx = launch_ros.actions.Node(
2929
package="yolox_ros_py", executable="yolox_onnx",output="screen",
3030
parameters=[
31-
{"image_size/width": 640},
32-
{"image_size/height": 480},
33-
3431
{"input_shape/width": 416},
3532
{"input_shape/height": 416},
3633

yolox_ros_py/launch/yolox_nano_onnx_gazebo.launch.py

Lines changed: 0 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -34,9 +34,6 @@ def generate_launch_description():
3434
yolox_onnx = launch_ros.actions.Node(
3535
package="yolox_ros_py", executable="yolox_onnx",output="screen",
3636
parameters=[
37-
{"image_size/width": 640},
38-
{"image_size/height": 480},
39-
4037
{"input_shape/width": 416},
4138
{"input_shape/height": 416},
4239

yolox_ros_py/launch/yolox_nano_onnx_picture.launch.py

Lines changed: 0 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -34,9 +34,6 @@ def generate_launch_description():
3434
yolox_onnx = launch_ros.actions.Node(
3535
package="yolox_ros_py", executable="yolox_onnx",output="screen",
3636
parameters=[
37-
{"image_size/width": 640},
38-
{"image_size/height": 480},
39-
4037
{"input_shape/width": 416},
4138
{"input_shape/height": 416},
4239

yolox_ros_py/launch/yolox_nano_onnx_youtube.launch.py

Lines changed: 0 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -36,9 +36,6 @@ def generate_launch_description():
3636
yolox_onnx = launch_ros.actions.Node(
3737
package="yolox_ros_py", executable="yolox_onnx",output="screen",
3838
parameters=[
39-
{"image_size/width": 640},
40-
{"image_size/height": 360},
41-
4239
{"input_shape/width": 416},
4340
{"input_shape/height": 416},
4441

yolox_ros_py/launch/yolox_nano_openvino.launch.py

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -29,8 +29,6 @@ def generate_launch_description():
2929
yolox_openvino = launch_ros.actions.Node(
3030
package="yolox_ros_py", executable="yolox_openvino",output="screen",
3131
parameters=[
32-
{"image_size/width": 640},
33-
{"image_size/height": 480},
3432
{"device" : 'CPU'},
3533
{"model_path" : yolox_ros_share_dir+"/yolox_nano.onnx"},
3634
{"conf" : 0.3},

yolox_ros_py/launch/yolox_nano_torch_cpu_camera.launch.py

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -26,8 +26,6 @@ def generate_launch_description():
2626
yolox_ros = launch_ros.actions.Node(
2727
package="yolox_ros_py", executable="yolox_ros",
2828
parameters=[
29-
{"image_size/width": 640},
30-
{"image_size/height": 480},
3129
{"yolox_exp_py" : yolox_ros_share_dir+'/yolox_nano.py'},
3230
{"device" : 'cpu'},
3331
{"fp16" : True},

yolox_ros_py/launch/yolox_nano_torch_gpu_camera.launch.py

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -26,8 +26,6 @@ def generate_launch_description():
2626
yolox_ros = launch_ros.actions.Node(
2727
package="yolox_ros_py", executable="yolox_ros",
2828
parameters=[
29-
{"image_size/width": 640},
30-
{"image_size/height": 480},
3129
{"yolox_exp_py" : yolox_ros_share_dir+'/yolox_nano.py'},
3230
{"device" : 'gpu'},
3331
{"fp16" : True},

yolox_ros_py/yolox_ros_py/yolox_onnx.py

Lines changed: 13 additions & 86 deletions
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,8 @@
1515
from yolox.data.datasets import COCO_CLASSES
1616
from yolox.utils import mkdir, multiclass_nms, demo_postprocess, vis
1717

18+
from .yolox_ros_py_utils.utils import yolox_py
19+
1820
# ROS2 =====================================
1921
import rclpy
2022
from rclpy.node import Node
@@ -31,100 +33,28 @@
3133
# from darkself.net_ros_msgs.msg import BoundingBoxes
3234
# from darkself.net_ros_msgs.msg import BoundingBox
3335

34-
class yolox_ros(Node):
36+
class yolox_ros(yolox_py):
3537
def __init__(self) -> None:
3638

3739
# ROS2 init
38-
super().__init__('yolox_ros')
39-
40-
self.setting_yolox_exp()
40+
super().__init__('yolox_ros', load_params=True)
4141

4242
if (self.imshow_isshow):
4343
cv2.namedWindow("YOLOX")
4444

4545
self.bridge = CvBridge()
4646

4747
self.pub = self.create_publisher(BoundingBoxes,"yolox/bounding_boxes", 10)
48-
self.pub_image = self.create_publisher(Image,"yolox/image_raw", 10)
49-
50-
if (self.sensor_qos_mode):
51-
self.sub = self.create_subscription(Image,"image_raw",self.imageflow_callback, qos_profile_sensor_data)
52-
else:
53-
self.sub = self.create_subscription(Image,"image_raw",self.imageflow_callback, 10)
54-
55-
def setting_yolox_exp(self) -> None:
56-
# set environment variables for distributed training
57-
58-
# ==============================================================
59-
60-
ONNX_PATH = './install/yolox_ros_py/share/yolox_ros_py/yolox_nano.onnx'
61-
62-
self.declare_parameter('imshow_isshow',True)
63-
64-
self.declare_parameter('model_path', ONNX_PATH)
65-
self.declare_parameter('conf', 0.3)
66-
self.declare_parameter('with_p6', False)
67-
self.declare_parameter('input_shape/width', 416)
68-
self.declare_parameter('input_shape/height', 416)
69-
70-
self.declare_parameter('image_size/width', 640)
71-
self.declare_parameter('image_size/height', 480)
72-
73-
self.declare_parameter('sensor_qos_mode', False)
74-
75-
# =============================================================
76-
self.imshow_isshow = self.get_parameter('imshow_isshow').value
77-
78-
self.model_path = self.get_parameter('model_path').value
79-
self.conf = self.get_parameter('conf').value
80-
81-
self.image_size_w = self.get_parameter('image_size/width').value
82-
self.image_size_h = self.get_parameter('image_size/height').value
83-
self.input_shape_w = self.get_parameter('input_shape/width').value
84-
self.input_shape_h = self.get_parameter('input_shape/height').value
85-
86-
self.sensor_qos_mode = self.get_parameter('sensor_qos_mode').value
48+
# self.pub_image = self.create_publisher(Image,"yolox/image_raw", 10)
8749

88-
# ==============================================================
89-
self.with_p6 = self.get_parameter('with_p6').value
90-
91-
self.get_logger().info('model_path: {}'.format(self.model_path))
92-
self.get_logger().info('conf: {}'.format(self.conf))
93-
self.get_logger().info('input_shape: {}'.format((self.input_shape_w, self.input_shape_h)))
94-
self.get_logger().info('image_size: {}'.format((self.image_size_w, self.image_size_h)))
95-
96-
self.get_logger().info('with_p6: {}'.format(self.with_p6))
97-
self.get_logger().info('sensor_qos_mode: {}'.format(self.sensor_qos_mode))
98-
99-
100-
self.input_shape = (self.input_shape_h, self.input_shape_w)
101-
102-
103-
def yolox2bboxes_msgs(self, bboxes, scores, cls, cls_names, img_header:Header):
104-
bboxes_msg = BoundingBoxes()
105-
bboxes_msg.header = img_header
106-
i = 0
107-
for bbox in bboxes:
108-
one_box = BoundingBox()
109-
one_box.xmin = int(bbox[0])
110-
one_box.ymin = int(bbox[1])
111-
one_box.xmax = int(bbox[2])
112-
one_box.ymax = int(bbox[3])
113-
one_box.probability = float(scores[i])
114-
one_box.class_id = str(cls_names[int(cls[i])])
115-
bboxes_msg.bounding_boxes.append(one_box)
116-
i = i+1
117-
118-
return bboxes_msg
50+
self.sub = self.create_subscription(Image,"image_raw",self.imageflow_callback, self.qos_image_sub)
11951

12052
def imageflow_callback(self,msg:Image) -> None:
12153
try:
12254
# fps start
12355
start_time = cv2.getTickCount()
12456
bboxes = BoundingBoxes()
12557
origin_img = self.bridge.imgmsg_to_cv2(msg,"bgr8")
126-
# resize
127-
origin_img = cv2.resize(origin_img, (self.image_size_w, self.image_size_h))
12858

12959
# preprocess
13060
img, self.ratio = preprocess(origin_img, self.input_shape)
@@ -145,39 +75,36 @@ def imageflow_callback(self,msg:Image) -> None:
14575
boxes_xyxy[:, 2] = boxes[:, 0] + boxes[:, 2]/2.
14676
boxes_xyxy[:, 3] = boxes[:, 1] + boxes[:, 3]/2.
14777
boxes_xyxy /= self.ratio
148-
dets = multiclass_nms(boxes_xyxy, scores, nms_thr=0.45, score_thr=self.conf)
78+
dets = multiclass_nms(boxes_xyxy, scores, nms_thr=self.nms_th, score_thr=self.conf)
14979
if dets is not None:
15080
self.final_boxes, self.final_scores, self.final_cls_inds = dets[:, :4], dets[:, 4], dets[:, 5]
15181
origin_img = vis(origin_img, self.final_boxes, self.final_scores, self.final_cls_inds,
15282
conf=self.conf, class_names=COCO_CLASSES)
153-
83+
15484
end_time = cv2.getTickCount()
15585
time_took = (end_time - start_time) / cv2.getTickFrequency()
156-
86+
15787
# rclpy log FPS
15888
self.get_logger().info(f'FPS: {1 / time_took}')
15989

16090
try:
161-
bboxes = self.yolox2bboxes_msgs(dets[:, :4], self.final_scores, self.final_cls_inds, COCO_CLASSES, msg.header)
162-
# self.get_logger().info(f'bboxes: {bboxes}')
91+
bboxes = self.yolox2bboxes_msgs(dets[:, :4], self.final_scores, self.final_cls_inds, COCO_CLASSES, msg.header, origin_img)
16392
if (self.imshow_isshow):
16493
cv2.imshow("YOLOX",origin_img)
16594
cv2.waitKey(1)
166-
95+
16796
except:
168-
# self.get_logger().info('No object detected')
16997
if (self.imshow_isshow):
17098
cv2.imshow("YOLOX",origin_img)
17199
cv2.waitKey(1)
172100

173101
self.pub.publish(bboxes)
174-
self.pub_image.publish(self.bridge.cv2_to_imgmsg(origin_img,"bgr8"))
102+
# self.pub_image.publish(self.bridge.cv2_to_imgmsg(origin_img,"bgr8"))
175103

176104
except Exception as e:
177105
self.get_logger().info(f'Error: {e}')
178106
pass
179107

180-
181108
def ros_main(args = None):
182109
rclpy.init(args=args)
183110
ros_class = yolox_ros()
@@ -189,6 +116,6 @@ def ros_main(args = None):
189116
finally:
190117
ros_class.destroy_node()
191118
rclpy.shutdown()
192-
119+
193120
if __name__ == "__main__":
194121
ros_main()

yolox_ros_py/yolox_ros_py/yolox_openvino.py

Lines changed: 11 additions & 62 deletions
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,8 @@
1515
from yolox.data.datasets import COCO_CLASSES
1616
from yolox.utils import multiclass_nms, demo_postprocess, vis
1717

18+
from .yolox_ros_py_utils.utils import yolox_py
19+
1820
# ROS2 =====================================
1921
import rclpy
2022
from rclpy.node import Node
@@ -31,11 +33,11 @@
3133
# from darkself.net_ros_msgs.msg import BoundingBoxes
3234
# from darkself.net_ros_msgs.msg import BoundingBox
3335

34-
class yolox_ros(Node):
36+
class yolox_ros(yolox_py):
3537
def __init__(self) -> None:
3638

3739
# ROS2 init
38-
super().__init__('yolox_ros')
40+
super().__init__('yolox_ros', load_params=True)
3941

4042
self.setting_yolox_exp()
4143

@@ -45,43 +47,14 @@ def __init__(self) -> None:
4547
self.bridge = CvBridge()
4648

4749
self.pub = self.create_publisher(BoundingBoxes,"yolox/bounding_boxes", 10)
48-
self.pub_image = self.create_publisher(Image,"yolox/image_raw", 10)
49-
if (self.sensor_qos_mode):
50-
self.sub = self.create_subscription(Image,"image_raw",self.imageflow_callback, qos_profile_sensor_data)
51-
else:
52-
self.sub = self.create_subscription(Image,"image_raw",self.imageflow_callback, 10)
50+
# self.pub_image = self.create_publisher(Image,"yolox/image_raw", 10)
51+
52+
self.sub = self.create_subscription(Image,"image_raw",self.imageflow_callback, self.qos_image_sub)
5353

5454
def setting_yolox_exp(self) -> None:
5555
# set environment variables for distributed training
5656

57-
# ==============================================================
58-
59-
WEIGHTS_PATH = '/home/ubuntu/ros2_ws/install/yolox_ros_py/share/yolox_ros_py/yolox_s.xml'
60-
61-
self.declare_parameter('imshow_isshow',True)
62-
63-
self.declare_parameter('model_path', WEIGHTS_PATH)
64-
self.declare_parameter('conf', 0.3)
65-
self.declare_parameter('device', "CPU")
66-
67-
self.declare_parameter('image_size/width', 640)
68-
self.declare_parameter('image_size/height', 480)
69-
70-
self.declare_parameter('sensor_qos_mode', False)
71-
72-
# =============================================================
73-
self.imshow_isshow = self.get_parameter('imshow_isshow').value
74-
75-
self.model_path = self.get_parameter('model_path').value
76-
self.conf = self.get_parameter('conf').value
77-
self.device = self.get_parameter('device').value
78-
79-
self.input_image_w = self.get_parameter('image_size/width').value
80-
self.input_image_h = self.get_parameter('image_size/height').value
81-
82-
self.sensor_qos_mode = self.get_parameter('sensor_qos_mode').value
83-
84-
# ==============================================================
57+
8558

8659
print('Creating Inference Engine')
8760
ie = IECore()
@@ -101,32 +74,12 @@ def setting_yolox_exp(self) -> None:
10174
print('Loading the model to the plugin')
10275
self.exec_net = ie.load_network(network=self.net, device_name=self.device)
10376

104-
105-
def yolox2bboxes_msgs(self, bboxes, scores, cls, cls_names, img_header:Header):
106-
bboxes_msg = BoundingBoxes()
107-
bboxes_msg.header = img_header
108-
i = 0
109-
for bbox in bboxes:
110-
one_box = BoundingBox()
111-
one_box.xmin = int(bbox[0])
112-
one_box.ymin = int(bbox[1])
113-
one_box.xmax = int(bbox[2])
114-
one_box.ymax = int(bbox[3])
115-
one_box.probability = float(scores[i])
116-
one_box.class_id = str(cls_names[int(cls[i])])
117-
bboxes_msg.bounding_boxes.append(one_box)
118-
i = i+1
119-
120-
return bboxes_msg
121-
12277
def imageflow_callback(self,msg:Image) -> None:
12378
try:
12479
# fps start
12580
start_time = cv2.getTickCount()
12681
bboxes = BoundingBoxes()
127-
img_rgb = self.bridge.imgmsg_to_cv2(msg,"bgr8")
128-
# resize
129-
origin_img = cv2.resize(img_rgb, (self.input_image_w, self.input_image_h))
82+
origin_img = self.bridge.imgmsg_to_cv2(msg,"bgr8")
13083
# deep copy
13184
nodetect_image = copy.deepcopy(origin_img)
13285

@@ -165,24 +118,20 @@ def imageflow_callback(self,msg:Image) -> None:
165118

166119
# rclpy log FPS
167120
self.get_logger().info(f'FPS: {1 / time_took}')
168-
169-
self.get_logger().info(f'Width: {self.input_image_w}, Height: {self.input_image_h}')
170121

171122
try:
172-
bboxes = self.yolox2bboxes_msgs(dets[:, :4], final_scores, final_cls_inds, COCO_CLASSES, msg.header)
173-
# self.get_logger().info(f'bboxes: {bboxes}')
123+
bboxes = self.yolox2bboxes_msgs(dets[:, :4], final_scores, final_cls_inds, COCO_CLASSES, msg.header, origin_img)
174124
if (self.imshow_isshow):
175125
cv2.imshow("YOLOX",origin_img)
176126
cv2.waitKey(1)
177127

178128
except:
179-
# self.get_logger().info('No object detected')
180129
if (self.imshow_isshow):
181130
cv2.imshow("YOLOX",origin_img)
182131
cv2.waitKey(1)
183132

184133
self.pub.publish(bboxes)
185-
self.pub_image.publish(self.bridge.cv2_to_imgmsg(nodetect_image,"bgr8"))
134+
# self.pub_image.publish(self.bridge.cv2_to_imgmsg(nodetect_image,"bgr8"))
186135

187136
except Exception as e:
188137
self.get_logger().info(f'Error: {e}')

0 commit comments

Comments
 (0)