1515from yolox .data .datasets import COCO_CLASSES
1616from yolox .utils import mkdir , multiclass_nms , demo_postprocess , vis
1717
18+ from .yolox_ros_py_utils .utils import yolox_py
19+
1820# ROS2 =====================================
1921import rclpy
2022from rclpy .node import Node
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-
181108def 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+
193120if __name__ == "__main__" :
194121 ros_main ()
0 commit comments