From cca2262f114d459d30d9ad0ca8942338d3e4d99e Mon Sep 17 00:00:00 2001 From: Ar-Ray-code Date: Mon, 9 May 2022 11:22:34 +0900 Subject: [PATCH 1/3] update launch.py --- README.md | 6 +- ....py => yolox_lite_tflite_camera.launch.py} | 0 ...ch.py => yolox_nano_onnx_camera.launch.py} | 0 .../launch/yolox_nano_onnx_picture.launch.py | 58 +++++++++++++++++++ .../launch/yolox_nano_onnx_youtube.launch.py | 1 - ... => yolox_nano_torch_cpu_camera.launch.py} | 0 ... => yolox_nano_torch_gpu_camera.launch.py} | 3 - 7 files changed, 61 insertions(+), 7 deletions(-) rename yolox_ros_py/launch/{yolox_tflite.launch.py => yolox_lite_tflite_camera.launch.py} (100%) rename yolox_ros_py/launch/{yolox_nano_onnx.launch.py => yolox_nano_onnx_camera.launch.py} (100%) create mode 100644 yolox_ros_py/launch/yolox_nano_onnx_picture.launch.py rename yolox_ros_py/launch/{yolox_nano_cpu.launch.py => yolox_nano_torch_cpu_camera.launch.py} (100%) rename yolox_ros_py/launch/{yolox_nano.launch.py => yolox_nano_torch_gpu_camera.launch.py} (97%) diff --git a/README.md b/README.md index 88f1c51..c009840 100644 --- a/README.md +++ b/README.md @@ -10,9 +10,9 @@ | Base | ROS2 C++ | ROS2 Python | | --------------- | -------- | ----------- | -| CPU | | ✅ | -| CUDA | | ✅ | -| CUDA (FP16) | | ✅ | +| PyTorch | | ✅ | +| PyTorch(CUDA) | | ✅ | +| PyTorch(CUDA-FP16) | | ✅ | | TensorRT (CUDA) | ✅ | | | OpenVINO | ✅ | ✅ | | ONNX Runtime | | ✅ | diff --git a/yolox_ros_py/launch/yolox_tflite.launch.py b/yolox_ros_py/launch/yolox_lite_tflite_camera.launch.py similarity index 100% rename from yolox_ros_py/launch/yolox_tflite.launch.py rename to yolox_ros_py/launch/yolox_lite_tflite_camera.launch.py diff --git a/yolox_ros_py/launch/yolox_nano_onnx.launch.py b/yolox_ros_py/launch/yolox_nano_onnx_camera.launch.py similarity index 100% rename from yolox_ros_py/launch/yolox_nano_onnx.launch.py rename to yolox_ros_py/launch/yolox_nano_onnx_camera.launch.py diff --git a/yolox_ros_py/launch/yolox_nano_onnx_picture.launch.py b/yolox_ros_py/launch/yolox_nano_onnx_picture.launch.py new file mode 100644 index 0000000..a31b80b --- /dev/null +++ b/yolox_ros_py/launch/yolox_nano_onnx_picture.launch.py @@ -0,0 +1,58 @@ +from matplotlib import image +import launch +import launch_ros.actions +from launch.actions import DeclareLaunchArgument +from ament_index_python.packages import get_package_share_directory +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration + +from urllib.request import urlretrieve +import os + +def generate_launch_description(): + yolox_ros_share_dir = get_package_share_directory('yolox_ros_py') + + dog_path = os.path.join(yolox_ros_share_dir, "./", "dog.jpg") + url = "https://raw.githubusercontent.com/pjreddie/darknet/master/data/dog.jpg" + if not os.path.exists(dog_path): + os.system("wget {} -O {}".format(url, dog_path)) + + + image_path = LaunchConfiguration('image_path', default=dog_path) + image_path_arg = DeclareLaunchArgument( + 'image_path', + default_value=dog_path, + description='Image path' + ) + + image_pub = launch_ros.actions.Node( + package='image_publisher', + executable='image_publisher_node', + name='image_publisher', + arguments=[image_path], + ) + yolox_onnx = launch_ros.actions.Node( + package="yolox_ros_py", executable="yolox_onnx",output="screen", + parameters=[ + {"image_size/width": 640}, + {"image_size/height": 480}, + + {"input_shape/width": 416}, + {"input_shape/height": 416}, + + {"with_p6" : False}, + {"model_path" : yolox_ros_share_dir+"/yolox_nano.onnx"}, + {"conf" : 0.3}, + ], + ) + + rqt_graph = launch_ros.actions.Node( + package="rqt_graph", executable="rqt_graph", + ) + + return launch.LaunchDescription([ + image_path_arg, + image_pub, + yolox_onnx, + # rqt_graph + ]) \ No newline at end of file diff --git a/yolox_ros_py/launch/yolox_nano_onnx_youtube.launch.py b/yolox_ros_py/launch/yolox_nano_onnx_youtube.launch.py index 8b37e79..a978e3f 100644 --- a/yolox_ros_py/launch/yolox_nano_onnx_youtube.launch.py +++ b/yolox_ros_py/launch/yolox_nano_onnx_youtube.launch.py @@ -7,7 +7,6 @@ from launch.launch_description_sources import PythonLaunchDescriptionSource import launch_ros - def generate_launch_description(): yolox_ros_share_dir = get_package_share_directory('yolox_ros_py') youtube_publisher_share_dir = get_package_share_directory('youtube_publisher') diff --git a/yolox_ros_py/launch/yolox_nano_cpu.launch.py b/yolox_ros_py/launch/yolox_nano_torch_cpu_camera.launch.py similarity index 100% rename from yolox_ros_py/launch/yolox_nano_cpu.launch.py rename to yolox_ros_py/launch/yolox_nano_torch_cpu_camera.launch.py diff --git a/yolox_ros_py/launch/yolox_nano.launch.py b/yolox_ros_py/launch/yolox_nano_torch_gpu_camera.launch.py similarity index 97% rename from yolox_ros_py/launch/yolox_nano.launch.py rename to yolox_ros_py/launch/yolox_nano_torch_gpu_camera.launch.py index ff9e6e5..661e8cf 100644 --- a/yolox_ros_py/launch/yolox_nano.launch.py +++ b/yolox_ros_py/launch/yolox_nano_torch_gpu_camera.launch.py @@ -5,9 +5,6 @@ from launch.launch_description_sources import PythonLaunchDescriptionSource from launch.substitutions import LaunchConfiguration -from urllib.request import urlretrieve -import os - def generate_launch_description(): yolox_ros_share_dir = get_package_share_directory('yolox_ros_py') From 27b408392d424871d270694738ecd5c7db7229dd Mon Sep 17 00:00:00 2001 From: Ar-Ray-code Date: Mon, 9 May 2022 14:49:17 +0900 Subject: [PATCH 2/3] update yolox_py --- .../launch/yolox_lite_tflite_camera.launch.py | 4 +- .../launch/yolox_nano_onnx_camera.launch.py | 3 - .../launch/yolox_nano_onnx_gazebo.launch.py | 3 - .../launch/yolox_nano_onnx_picture.launch.py | 3 - .../launch/yolox_nano_onnx_youtube.launch.py | 3 - .../launch/yolox_nano_openvino.launch.py | 2 - .../yolox_nano_torch_cpu_camera.launch.py | 2 - .../yolox_nano_torch_gpu_camera.launch.py | 2 - yolox_ros_py/yolox_ros_py/yolox_onnx.py | 99 +++------------- yolox_ros_py/yolox_ros_py/yolox_openvino.py | 73 ++---------- yolox_ros_py/yolox_ros_py/yolox_ros.py | 64 +++-------- .../yolox_ros_py/yolox_ros_py_utils/utils.py | 106 ++++++++++++++++++ yolox_ros_py/yolox_ros_py/yolox_tflite.py | 87 ++------------ 13 files changed, 159 insertions(+), 292 deletions(-) create mode 100644 yolox_ros_py/yolox_ros_py/yolox_ros_py_utils/utils.py diff --git a/yolox_ros_py/launch/yolox_lite_tflite_camera.launch.py b/yolox_ros_py/launch/yolox_lite_tflite_camera.launch.py index 50b9230..101ae1f 100644 --- a/yolox_ros_py/launch/yolox_lite_tflite_camera.launch.py +++ b/yolox_ros_py/launch/yolox_lite_tflite_camera.launch.py @@ -37,8 +37,8 @@ def generate_launch_description(): yolox_tflite = launch_ros.actions.Node( package="yolox_ros_py", executable="yolox_tflite",output="screen", parameters=[ - {"model" : yolox_ros_share_dir+"/model.tflite"}, - {"score_th" : 0.4}, + {"model_path" : yolox_ros_share_dir+"/model.tflite"}, + {"conf" : 0.4}, {"nms_th" : 0.5}, {"input_shape/height" : 192}, {"input_shape/width" : 192} diff --git a/yolox_ros_py/launch/yolox_nano_onnx_camera.launch.py b/yolox_ros_py/launch/yolox_nano_onnx_camera.launch.py index 7ac2f48..03cde5f 100644 --- a/yolox_ros_py/launch/yolox_nano_onnx_camera.launch.py +++ b/yolox_ros_py/launch/yolox_nano_onnx_camera.launch.py @@ -28,9 +28,6 @@ def generate_launch_description(): yolox_onnx = launch_ros.actions.Node( package="yolox_ros_py", executable="yolox_onnx",output="screen", parameters=[ - {"image_size/width": 640}, - {"image_size/height": 480}, - {"input_shape/width": 416}, {"input_shape/height": 416}, diff --git a/yolox_ros_py/launch/yolox_nano_onnx_gazebo.launch.py b/yolox_ros_py/launch/yolox_nano_onnx_gazebo.launch.py index 872b144..b882670 100644 --- a/yolox_ros_py/launch/yolox_nano_onnx_gazebo.launch.py +++ b/yolox_ros_py/launch/yolox_nano_onnx_gazebo.launch.py @@ -34,9 +34,6 @@ def generate_launch_description(): yolox_onnx = launch_ros.actions.Node( package="yolox_ros_py", executable="yolox_onnx",output="screen", parameters=[ - {"image_size/width": 640}, - {"image_size/height": 480}, - {"input_shape/width": 416}, {"input_shape/height": 416}, diff --git a/yolox_ros_py/launch/yolox_nano_onnx_picture.launch.py b/yolox_ros_py/launch/yolox_nano_onnx_picture.launch.py index a31b80b..dca3fbc 100644 --- a/yolox_ros_py/launch/yolox_nano_onnx_picture.launch.py +++ b/yolox_ros_py/launch/yolox_nano_onnx_picture.launch.py @@ -34,9 +34,6 @@ def generate_launch_description(): yolox_onnx = launch_ros.actions.Node( package="yolox_ros_py", executable="yolox_onnx",output="screen", parameters=[ - {"image_size/width": 640}, - {"image_size/height": 480}, - {"input_shape/width": 416}, {"input_shape/height": 416}, diff --git a/yolox_ros_py/launch/yolox_nano_onnx_youtube.launch.py b/yolox_ros_py/launch/yolox_nano_onnx_youtube.launch.py index a978e3f..698167c 100644 --- a/yolox_ros_py/launch/yolox_nano_onnx_youtube.launch.py +++ b/yolox_ros_py/launch/yolox_nano_onnx_youtube.launch.py @@ -36,9 +36,6 @@ def generate_launch_description(): yolox_onnx = launch_ros.actions.Node( package="yolox_ros_py", executable="yolox_onnx",output="screen", parameters=[ - {"image_size/width": 640}, - {"image_size/height": 360}, - {"input_shape/width": 416}, {"input_shape/height": 416}, diff --git a/yolox_ros_py/launch/yolox_nano_openvino.launch.py b/yolox_ros_py/launch/yolox_nano_openvino.launch.py index 3d3fb9c..0af87b9 100644 --- a/yolox_ros_py/launch/yolox_nano_openvino.launch.py +++ b/yolox_ros_py/launch/yolox_nano_openvino.launch.py @@ -29,8 +29,6 @@ def generate_launch_description(): yolox_openvino = launch_ros.actions.Node( package="yolox_ros_py", executable="yolox_openvino",output="screen", parameters=[ - {"image_size/width": 640}, - {"image_size/height": 480}, {"device" : 'CPU'}, {"model_path" : yolox_ros_share_dir+"/yolox_nano.onnx"}, {"conf" : 0.3}, diff --git a/yolox_ros_py/launch/yolox_nano_torch_cpu_camera.launch.py b/yolox_ros_py/launch/yolox_nano_torch_cpu_camera.launch.py index a4d9bf9..e7957dd 100644 --- a/yolox_ros_py/launch/yolox_nano_torch_cpu_camera.launch.py +++ b/yolox_ros_py/launch/yolox_nano_torch_cpu_camera.launch.py @@ -26,8 +26,6 @@ def generate_launch_description(): yolox_ros = launch_ros.actions.Node( package="yolox_ros_py", executable="yolox_ros", parameters=[ - {"image_size/width": 640}, - {"image_size/height": 480}, {"yolox_exp_py" : yolox_ros_share_dir+'/yolox_nano.py'}, {"device" : 'cpu'}, {"fp16" : True}, diff --git a/yolox_ros_py/launch/yolox_nano_torch_gpu_camera.launch.py b/yolox_ros_py/launch/yolox_nano_torch_gpu_camera.launch.py index 661e8cf..3d2b606 100644 --- a/yolox_ros_py/launch/yolox_nano_torch_gpu_camera.launch.py +++ b/yolox_ros_py/launch/yolox_nano_torch_gpu_camera.launch.py @@ -26,8 +26,6 @@ def generate_launch_description(): yolox_ros = launch_ros.actions.Node( package="yolox_ros_py", executable="yolox_ros", parameters=[ - {"image_size/width": 640}, - {"image_size/height": 480}, {"yolox_exp_py" : yolox_ros_share_dir+'/yolox_nano.py'}, {"device" : 'gpu'}, {"fp16" : True}, diff --git a/yolox_ros_py/yolox_ros_py/yolox_onnx.py b/yolox_ros_py/yolox_ros_py/yolox_onnx.py index 98df2d7..4c24c21 100644 --- a/yolox_ros_py/yolox_ros_py/yolox_onnx.py +++ b/yolox_ros_py/yolox_ros_py/yolox_onnx.py @@ -15,6 +15,8 @@ from yolox.data.datasets import COCO_CLASSES from yolox.utils import mkdir, multiclass_nms, demo_postprocess, vis +from .yolox_ros_py_utils.utils import yolox_py + # ROS2 ===================================== import rclpy from rclpy.node import Node @@ -31,13 +33,11 @@ # from darkself.net_ros_msgs.msg import BoundingBoxes # from darkself.net_ros_msgs.msg import BoundingBox -class yolox_ros(Node): +class yolox_ros(yolox_py): def __init__(self) -> None: # ROS2 init - super().__init__('yolox_ros') - - self.setting_yolox_exp() + super().__init__('yolox_ros', load_params=True) if (self.imshow_isshow): cv2.namedWindow("YOLOX") @@ -45,77 +45,9 @@ def __init__(self) -> None: self.bridge = CvBridge() self.pub = self.create_publisher(BoundingBoxes,"yolox/bounding_boxes", 10) - self.pub_image = self.create_publisher(Image,"yolox/image_raw", 10) - - if (self.sensor_qos_mode): - self.sub = self.create_subscription(Image,"image_raw",self.imageflow_callback, qos_profile_sensor_data) - else: - self.sub = self.create_subscription(Image,"image_raw",self.imageflow_callback, 10) - - def setting_yolox_exp(self) -> None: - # set environment variables for distributed training - - # ============================================================== - - ONNX_PATH = './install/yolox_ros_py/share/yolox_ros_py/yolox_nano.onnx' - - self.declare_parameter('imshow_isshow',True) - - self.declare_parameter('model_path', ONNX_PATH) - self.declare_parameter('conf', 0.3) - self.declare_parameter('with_p6', False) - self.declare_parameter('input_shape/width', 416) - self.declare_parameter('input_shape/height', 416) - - self.declare_parameter('image_size/width', 640) - self.declare_parameter('image_size/height', 480) - - self.declare_parameter('sensor_qos_mode', False) - - # ============================================================= - self.imshow_isshow = self.get_parameter('imshow_isshow').value - - self.model_path = self.get_parameter('model_path').value - self.conf = self.get_parameter('conf').value - - self.image_size_w = self.get_parameter('image_size/width').value - self.image_size_h = self.get_parameter('image_size/height').value - self.input_shape_w = self.get_parameter('input_shape/width').value - self.input_shape_h = self.get_parameter('input_shape/height').value - - self.sensor_qos_mode = self.get_parameter('sensor_qos_mode').value + # self.pub_image = self.create_publisher(Image,"yolox/image_raw", 10) - # ============================================================== - self.with_p6 = self.get_parameter('with_p6').value - - self.get_logger().info('model_path: {}'.format(self.model_path)) - self.get_logger().info('conf: {}'.format(self.conf)) - self.get_logger().info('input_shape: {}'.format((self.input_shape_w, self.input_shape_h))) - self.get_logger().info('image_size: {}'.format((self.image_size_w, self.image_size_h))) - - self.get_logger().info('with_p6: {}'.format(self.with_p6)) - self.get_logger().info('sensor_qos_mode: {}'.format(self.sensor_qos_mode)) - - - self.input_shape = (self.input_shape_h, self.input_shape_w) - - - def yolox2bboxes_msgs(self, bboxes, scores, cls, cls_names, img_header:Header): - bboxes_msg = BoundingBoxes() - bboxes_msg.header = img_header - i = 0 - for bbox in bboxes: - one_box = BoundingBox() - one_box.xmin = int(bbox[0]) - one_box.ymin = int(bbox[1]) - one_box.xmax = int(bbox[2]) - one_box.ymax = int(bbox[3]) - one_box.probability = float(scores[i]) - one_box.class_id = str(cls_names[int(cls[i])]) - bboxes_msg.bounding_boxes.append(one_box) - i = i+1 - - return bboxes_msg + self.sub = self.create_subscription(Image,"image_raw",self.imageflow_callback, self.qos_image_sub) def imageflow_callback(self,msg:Image) -> None: try: @@ -123,8 +55,6 @@ def imageflow_callback(self,msg:Image) -> None: start_time = cv2.getTickCount() bboxes = BoundingBoxes() origin_img = self.bridge.imgmsg_to_cv2(msg,"bgr8") - # resize - origin_img = cv2.resize(origin_img, (self.image_size_w, self.image_size_h)) # preprocess img, self.ratio = preprocess(origin_img, self.input_shape) @@ -145,39 +75,36 @@ def imageflow_callback(self,msg:Image) -> None: boxes_xyxy[:, 2] = boxes[:, 0] + boxes[:, 2]/2. boxes_xyxy[:, 3] = boxes[:, 1] + boxes[:, 3]/2. boxes_xyxy /= self.ratio - dets = multiclass_nms(boxes_xyxy, scores, nms_thr=0.45, score_thr=self.conf) + dets = multiclass_nms(boxes_xyxy, scores, nms_thr=self.nms_th, score_thr=self.conf) if dets is not None: self.final_boxes, self.final_scores, self.final_cls_inds = dets[:, :4], dets[:, 4], dets[:, 5] origin_img = vis(origin_img, self.final_boxes, self.final_scores, self.final_cls_inds, conf=self.conf, class_names=COCO_CLASSES) - + end_time = cv2.getTickCount() time_took = (end_time - start_time) / cv2.getTickFrequency() - + # rclpy log FPS self.get_logger().info(f'FPS: {1 / time_took}') try: - bboxes = self.yolox2bboxes_msgs(dets[:, :4], self.final_scores, self.final_cls_inds, COCO_CLASSES, msg.header) - # self.get_logger().info(f'bboxes: {bboxes}') + bboxes = self.yolox2bboxes_msgs(dets[:, :4], self.final_scores, self.final_cls_inds, COCO_CLASSES, msg.header, origin_img) if (self.imshow_isshow): cv2.imshow("YOLOX",origin_img) cv2.waitKey(1) - + except: - # self.get_logger().info('No object detected') if (self.imshow_isshow): cv2.imshow("YOLOX",origin_img) cv2.waitKey(1) self.pub.publish(bboxes) - self.pub_image.publish(self.bridge.cv2_to_imgmsg(origin_img,"bgr8")) + # self.pub_image.publish(self.bridge.cv2_to_imgmsg(origin_img,"bgr8")) except Exception as e: self.get_logger().info(f'Error: {e}') pass - def ros_main(args = None): rclpy.init(args=args) ros_class = yolox_ros() @@ -189,6 +116,6 @@ def ros_main(args = None): finally: ros_class.destroy_node() rclpy.shutdown() - + if __name__ == "__main__": ros_main() \ No newline at end of file diff --git a/yolox_ros_py/yolox_ros_py/yolox_openvino.py b/yolox_ros_py/yolox_ros_py/yolox_openvino.py index 945b352..a12e3c0 100644 --- a/yolox_ros_py/yolox_ros_py/yolox_openvino.py +++ b/yolox_ros_py/yolox_ros_py/yolox_openvino.py @@ -15,6 +15,8 @@ from yolox.data.datasets import COCO_CLASSES from yolox.utils import multiclass_nms, demo_postprocess, vis +from .yolox_ros_py_utils.utils import yolox_py + # ROS2 ===================================== import rclpy from rclpy.node import Node @@ -31,11 +33,11 @@ # from darkself.net_ros_msgs.msg import BoundingBoxes # from darkself.net_ros_msgs.msg import BoundingBox -class yolox_ros(Node): +class yolox_ros(yolox_py): def __init__(self) -> None: # ROS2 init - super().__init__('yolox_ros') + super().__init__('yolox_ros', load_params=True) self.setting_yolox_exp() @@ -45,43 +47,14 @@ def __init__(self) -> None: self.bridge = CvBridge() self.pub = self.create_publisher(BoundingBoxes,"yolox/bounding_boxes", 10) - self.pub_image = self.create_publisher(Image,"yolox/image_raw", 10) - if (self.sensor_qos_mode): - self.sub = self.create_subscription(Image,"image_raw",self.imageflow_callback, qos_profile_sensor_data) - else: - self.sub = self.create_subscription(Image,"image_raw",self.imageflow_callback, 10) + # self.pub_image = self.create_publisher(Image,"yolox/image_raw", 10) + + self.sub = self.create_subscription(Image,"image_raw",self.imageflow_callback, self.qos_image_sub) def setting_yolox_exp(self) -> None: # set environment variables for distributed training - # ============================================================== - - WEIGHTS_PATH = '/home/ubuntu/ros2_ws/install/yolox_ros_py/share/yolox_ros_py/yolox_s.xml' - - self.declare_parameter('imshow_isshow',True) - - self.declare_parameter('model_path', WEIGHTS_PATH) - self.declare_parameter('conf', 0.3) - self.declare_parameter('device', "CPU") - - self.declare_parameter('image_size/width', 640) - self.declare_parameter('image_size/height', 480) - - self.declare_parameter('sensor_qos_mode', False) - - # ============================================================= - self.imshow_isshow = self.get_parameter('imshow_isshow').value - - self.model_path = self.get_parameter('model_path').value - self.conf = self.get_parameter('conf').value - self.device = self.get_parameter('device').value - - self.input_image_w = self.get_parameter('image_size/width').value - self.input_image_h = self.get_parameter('image_size/height').value - - self.sensor_qos_mode = self.get_parameter('sensor_qos_mode').value - - # ============================================================== + print('Creating Inference Engine') ie = IECore() @@ -101,32 +74,12 @@ def setting_yolox_exp(self) -> None: print('Loading the model to the plugin') self.exec_net = ie.load_network(network=self.net, device_name=self.device) - - def yolox2bboxes_msgs(self, bboxes, scores, cls, cls_names, img_header:Header): - bboxes_msg = BoundingBoxes() - bboxes_msg.header = img_header - i = 0 - for bbox in bboxes: - one_box = BoundingBox() - one_box.xmin = int(bbox[0]) - one_box.ymin = int(bbox[1]) - one_box.xmax = int(bbox[2]) - one_box.ymax = int(bbox[3]) - one_box.probability = float(scores[i]) - one_box.class_id = str(cls_names[int(cls[i])]) - bboxes_msg.bounding_boxes.append(one_box) - i = i+1 - - return bboxes_msg - def imageflow_callback(self,msg:Image) -> None: try: # fps start start_time = cv2.getTickCount() bboxes = BoundingBoxes() - img_rgb = self.bridge.imgmsg_to_cv2(msg,"bgr8") - # resize - origin_img = cv2.resize(img_rgb, (self.input_image_w, self.input_image_h)) + origin_img = self.bridge.imgmsg_to_cv2(msg,"bgr8") # deep copy nodetect_image = copy.deepcopy(origin_img) @@ -165,24 +118,20 @@ def imageflow_callback(self,msg:Image) -> None: # rclpy log FPS self.get_logger().info(f'FPS: {1 / time_took}') - - self.get_logger().info(f'Width: {self.input_image_w}, Height: {self.input_image_h}') try: - bboxes = self.yolox2bboxes_msgs(dets[:, :4], final_scores, final_cls_inds, COCO_CLASSES, msg.header) - # self.get_logger().info(f'bboxes: {bboxes}') + bboxes = self.yolox2bboxes_msgs(dets[:, :4], final_scores, final_cls_inds, COCO_CLASSES, msg.header, origin_img) if (self.imshow_isshow): cv2.imshow("YOLOX",origin_img) cv2.waitKey(1) except: - # self.get_logger().info('No object detected') if (self.imshow_isshow): cv2.imshow("YOLOX",origin_img) cv2.waitKey(1) self.pub.publish(bboxes) - self.pub_image.publish(self.bridge.cv2_to_imgmsg(nodetect_image,"bgr8")) + # self.pub_image.publish(self.bridge.cv2_to_imgmsg(nodetect_image,"bgr8")) except Exception as e: self.get_logger().info(f'Error: {e}') diff --git a/yolox_ros_py/yolox_ros_py/yolox_ros.py b/yolox_ros_py/yolox_ros_py/yolox_ros.py index 97073e3..3f62dd7 100644 --- a/yolox_ros_py/yolox_ros_py/yolox_ros.py +++ b/yolox_ros_py/yolox_ros_py/yolox_ros.py @@ -19,6 +19,8 @@ from yolox.exp import get_exp from yolox.utils import fuse_model, get_model_info, postprocess, setup_logger, vis +from .yolox_ros_py_utils.utils import yolox_py + import rclpy from rclpy.node import Node @@ -112,18 +114,18 @@ def visual(self, output, img_info, cls_conf=0.35): return vis_res, bboxes, scores, cls, self.cls_names -class yolox_ros(Node): +class yolox_ros(yolox_py): def __init__(self) -> None: # ROS2 init - super().__init__('yolox_ros') + super().__init__('yolox_ros', load_params=False) self.setting_yolox_exp() self.bridge = CvBridge() self.pub = self.create_publisher(BoundingBoxes,"yolox/bounding_boxes", 10) - self.pub_image = self.create_publisher(Image,"yolox/image_raw", 10) + # self.pub_image = self.create_publisher(Image,"yolox/image_raw", 10) if (self.sensor_qos_mode): self.sub = self.create_subscription(Image,"image_raw",self.imageflow_callback, qos_profile_sensor_data) @@ -132,14 +134,11 @@ def __init__(self) -> None: def setting_yolox_exp(self) -> None: # set environment variables for distributed training - # ============================================================== WEIGHTS_PATH = '../../weights/yolox_nano.pth' self.declare_parameter('imshow_isshow',True) - - # self.declare_parameter('yolo_type','yolox-s') self.declare_parameter('yolox_exp_py', '') self.declare_parameter('fuse',False) @@ -155,17 +154,12 @@ def setting_yolox_exp(self) -> None: self.declare_parameter('threshold', 0.65) # --tsize -> resize self.declare_parameter('resize', 640) - - # resize input image - self.declare_parameter('image_size/width', 640) - self.declare_parameter('image_size/height', 480) self.declare_parameter('sensor_qos_mode', False) # ============================================================= self.imshow_isshow = self.get_parameter('imshow_isshow').value - # yolo_type = self.get_parameter('yolo_type').value exp_py = self.get_parameter('yolox_exp_py').value fuse = self.get_parameter('fuse').value @@ -178,17 +172,14 @@ def setting_yolox_exp(self) -> None: legacy = self.get_parameter('legacy').value threshold = self.get_parameter('threshold').value - resize = self.get_parameter('resize').value - self.input_width = self.get_parameter('image_size/width').value - self.input_height = self.get_parameter('image_size/height').value + input_shape_w = self.get_parameter('resize').value + input_shape_h = input_shape_w self.sensor_qos_mode = self.get_parameter('sensor_qos_mode').value # ============================================================== cudnn.benchmark = True - - # exp = get_exp(None, "yolox-s") exp = get_exp(exp_py, None) @@ -198,7 +189,7 @@ def setting_yolox_exp(self) -> None: exp.test_conf = conf # test conf exp.threshold = threshold # nms threshold - exp.test_size = (resize, resize) # Resize size + exp.test_size = (input_shape_h, input_shape_w) # test size model = exp.get_model() logger.info("Model Summary: {}".format(get_model_info(model, exp.test_size))) @@ -244,49 +235,30 @@ def setting_yolox_exp(self) -> None: self.predictor = Predictor(model, exp, COCO_CLASSES, trt_file, decoder, device, fp16, legacy) - def yolox2bboxes_msgs(self, bboxes, scores, cls, cls_names, img_header:Header): - bboxes_msg = BoundingBoxes() - bboxes_msg.header = img_header - i = 0 - for bbox in bboxes: - one_box = BoundingBox() - one_box.xmin = int(bbox[0]) - one_box.ymin = int(bbox[1]) - one_box.xmax = int(bbox[2]) - one_box.ymax = int(bbox[3]) - one_box.probability = float(scores[i]) - one_box.class_id = str(cls_names[int(cls[i])]) - bboxes_msg.bounding_boxes.append(one_box) - i = i+1 - - return bboxes_msg - def imageflow_callback(self,msg:Image) -> None: try: img_rgb = self.bridge.imgmsg_to_cv2(msg,"bgr8") - # resize - img_rgb = cv2.resize(img_rgb,(self.input_width,self.input_height)) - outputs, img_info = self.predictor.inference(img_rgb) try: result_img_rgb, bboxes, scores, cls, cls_names = self.predictor.visual(outputs[0], img_info) - bboxes = self.yolox2bboxes_msgs(bboxes, scores, cls, cls_names, msg.header) - - self.pub.publish(bboxes) - msg = self.bridge.cv2_to_imgmsg(img_rgb,"bgr8") - msg.header.frame_id = "camera" - self.pub_image.publish(msg) + bboxes_msg = self.yolox2bboxes_msgs(bboxes, scores, cls, cls_names, msg.header, img_rgb) + + self.pub.publish(bboxes_msg) + # msg = self.bridge.cv2_to_imgmsg(img_rgb,"bgr8") + # msg.header.frame_id = "camera" + # self.pub_image.publish(msg) if (self.imshow_isshow): cv2.imshow("YOLOX",result_img_rgb) cv2.waitKey(1) - - except: + + except Exception as e: if (self.imshow_isshow): cv2.imshow("YOLOX",img_rgb) cv2.waitKey(1) - except: + except Exception as e: + logger.error(e) pass def ros_main(args = None): diff --git a/yolox_ros_py/yolox_ros_py/yolox_ros_py_utils/utils.py b/yolox_ros_py/yolox_ros_py/yolox_ros_py_utils/utils.py new file mode 100644 index 0000000..5304892 --- /dev/null +++ b/yolox_ros_py/yolox_ros_py/yolox_ros_py_utils/utils.py @@ -0,0 +1,106 @@ +import numpy as np + +from bboxes_ex_msgs.msg import BoundingBoxes +from bboxes_ex_msgs.msg import BoundingBox + +# from darknet_ros_msgs.msg import BoundingBoxes +# from darknet_ros_msgs.msg import BoundingBox + +from rclpy.node import Node +from std_msgs.msg import Header +from rclpy.qos import qos_profile_sensor_data + +from loguru import logger +import sys + +class yolox_py(Node): + def __init__(self, name, load_params=True): + super().__init__(name) + if load_params: + self.parameter_ros2() + + def yolox2bboxes_msgs(self, bboxes, scores, cls, cls_names, img_header: Header, image: np.ndarray) -> BoundingBoxes: + bboxes_msg = BoundingBoxes() + bboxes_msg.header = img_header + i = 0 + for bbox in bboxes: + one_box = BoundingBox() + # if < 0 + if bbox[0] < 0: + bbox[0] = 0 + if bbox[1] < 0: + bbox[1] = 0 + if bbox[2] < 0: + bbox[2] = 0 + if bbox[3] < 0: + bbox[3] = 0 + one_box.xmin = int(bbox[0]) + one_box.ymin = int(bbox[1]) + one_box.xmax = int(bbox[2]) + one_box.ymax = int(bbox[3]) + + if "bboxes_ex_msgs" in sys.modules: + one_box.img_height = image.shape[0] + one_box.img_width = image.shape[1] + else: + pass + + one_box.probability = float(scores[i]) + one_box.class_id = str(cls_names[int(cls[i])]) + bboxes_msg.bounding_boxes.append(one_box) + i = i+1 + + return bboxes_msg + + def parameter_ros2(self): + # パラメータ設定 ################################################### + self.declare_parameter('model_path', './model/model.onnx') + # self.declare_parameter('score_th', 0.4) + self.declare_parameter('nms_th', 0.5) + self.declare_parameter('conf', 0.3) + self.declare_parameter('device', "CPU") + + self.declare_parameter('num_threads', None) + self.declare_parameter('input_shape/height', 416) + self.declare_parameter('input_shape/width', 416) + self.declare_parameter('imshow_isshow',True) + self.declare_parameter('with_p6', False) + + self.declare_parameter('sensor_qos_mode', False) + + # パラメータ取得 ################################################### + self.model_path = self.get_parameter('model_path').value + # self.score_th = self.get_parameter('score_th').value + self.nms_th = self.get_parameter('nms_th').value + self.conf = self.get_parameter('conf').value + self.device = self.get_parameter('device').value + + self.num_threads = self.get_parameter('num_threads').value + self.input_shape_h = self.get_parameter('input_shape/height').value + self.input_shape_w = self.get_parameter('input_shape/width').value + self.imshow_isshow = self.get_parameter('imshow_isshow').value + self.with_p6 = self.get_parameter('with_p6').value + + self.sensor_qos_mode = self.get_parameter('sensor_qos_mode').value + + if self.sensor_qos_mode: + self.qos_image_sub = qos_profile_sensor_data + else: + self.qos_image_sub = 10 + + self.input_shape = (self.input_shape_h, self.input_shape_w) + + + # ============================================================== + logger.info("parameters -------------------------------------------------") + logger.info("model_path: {}".format(self.model_path)) + logger.info("nms_th (ONNX): {}".format(self.nms_th)) + logger.info("conf: {}".format(self.conf)) + logger.info("device: {}".format(self.device)) + logger.info("num_threads: {}".format(self.num_threads)) + logger.info("input_shape: {}".format(self.input_shape)) + logger.info("imshow_isshow: {}".format(self.imshow_isshow)) + logger.info("with_p6 (ONNX): {}".format(self.with_p6)) + logger.info("sensor_qos_mode: {}".format(self.sensor_qos_mode)) + logger.info("-------------------------------------------------------------") + # ============================================================== diff --git a/yolox_ros_py/yolox_ros_py/yolox_tflite.py b/yolox_ros_py/yolox_ros_py/yolox_tflite.py index 37f2ccd..4001e66 100644 --- a/yolox_ros_py/yolox_ros_py/yolox_tflite.py +++ b/yolox_ros_py/yolox_ros_py/yolox_tflite.py @@ -21,6 +21,7 @@ from .module_tflite.detector import Detector from .module_tflite.demo import draw_debug +from .yolox_ros_py_utils.utils import yolox_py # ROS2 ===================================== import rclpy @@ -37,65 +38,32 @@ from bboxes_ex_msgs.msg import BoundingBoxes from bboxes_ex_msgs.msg import BoundingBox -class yolox_cpu(Node): +class yolox_cpu(yolox_py): def __init__(self): - super().__init__('yolox_cpu') - - # パラメータ設定 ################################################### - self.declare_parameter('model', './model/model.onnx') - self.declare_parameter('score_th', 0.4) - self.declare_parameter('nms_th', 0.5) - self.declare_parameter('num_threads', None) - self.declare_parameter('input_shape/height', 192) - self.declare_parameter('input_shape/width', 192) - - self.declare_parameter('image_size/width', 640) - self.declare_parameter('image_size/height', 480) - - self.declare_parameter('sensor_qos_mode', False) - - # パラメータ取得 ################################################### - self.model_path = self.get_parameter('model').value - self.score_th = self.get_parameter('score_th').value - self.nms_th = self.get_parameter('nms_th').value - self.num_threads = self.get_parameter('num_threads').value - self.input_shape_h = self.get_parameter('input_shape/height').value - self.input_shape_w = self.get_parameter('input_shape/width').value - - self.image_size_w = self.get_parameter('image_size/width').value - self.image_size_h = self.get_parameter('image_size/height').value - - self.sensor_qos_mode = self.get_parameter('sensor_qos_mode').value - - self.input_shape = (self.input_shape_h, self.input_shape_w) + super().__init__('yolox_cpu', load_params=True) self.bridge = CvBridge() self.yolox = Detector( model_path=self.model_path, input_shape=self.input_shape, - score_th=self.score_th, + score_th=self.conf, nms_th=self.nms_th, providers=['CPUExecutionProvider'], num_threads=self.num_threads, ) - if (self.sensor_qos_mode): - self.sub = self.create_subscription(Image,"image_raw",self.imageflow_callback, qos_profile_sensor_data) - else: - self.sub = self.create_subscription(Image,"image_raw",self.imageflow_callback, 10) + self.sub = self.create_subscription(Image,"image_raw",self.imageflow_callback, self.qos_image_sub) self.pub_detection = self.create_publisher( BoundingBoxes, - 'detection', + 'bounding_boxes', 10 ) def imageflow_callback(self, msg): start = time.time() image = self.bridge.imgmsg_to_cv2(msg, desired_encoding='bgr8') - # resize - image = cv2.resize(image, (self.image_size_w, self.image_size_h)) bboxes, scores, class_ids = self.yolox.inference(image) elapsed_time = time.time() - start fps = 1 / elapsed_time @@ -107,57 +75,20 @@ def imageflow_callback(self, msg): debug_image = draw_debug( image, elapsed_time, - self.score_th, + self.conf, bboxes, scores, class_ids, ) - # キー処理(ESC:終了) ############################################## - key = cv2.waitKey(1) - if key == 27: # ESC - pass - - # 画面反映 ######################################################### - debug_image = cv2.resize(debug_image, (640, 480)) cv2.imshow('debug_image', debug_image) + cv2.waitKey(1) - # データ出力 ####################################################### - bboxes_msg = self.yolox2bboxes_msgs(bboxes, scores, class_ids, COCO_CLASSES, msg.header) + bboxes_msg = self.yolox2bboxes_msgs(bboxes, scores, class_ids, COCO_CLASSES, msg.header, image) self.pub_detection.publish(bboxes_msg) - - # print self.get_logger().info('fps: %.2f' % fps) - def yolox2bboxes_msgs(self, bboxes, scores, cls, cls_names, img_header:Header): - bboxes_msg = BoundingBoxes() - bboxes_msg.header = img_header - i = 0 - for bbox in bboxes: - one_box = BoundingBox() - # if < 0 - if bbox[0] < 0: - bbox[0] = 0 - if bbox[1] < 0: - bbox[1] = 0 - if bbox[2] < 0: - bbox[2] = 0 - if bbox[3] < 0: - bbox[3] = 0 - one_box.xmin = int(bbox[0]) - one_box.ymin = int(bbox[1]) - one_box.xmax = int(bbox[2]) - one_box.ymax = int(bbox[3]) - one_box.img_height = self.image_h - one_box.img_width = self.image_w - one_box.probability = float(scores[i]) - one_box.class_id = str(cls_names[int(cls[i])]) - bboxes_msg.bounding_boxes.append(one_box) - i = i+1 - - return bboxes_msg - def __del__(self): cv2.destroyAllWindows() self.pub_detection.destroy() From 5989847c19d97106883e160c23be2bc30eed44cf Mon Sep 17 00:00:00 2001 From: Ar-Ray-code Date: Mon, 9 May 2022 14:58:29 +0900 Subject: [PATCH 3/3] version is 0.3.1 --- README.md | 2 +- yolox_ros_py/package.xml | 2 +- yolox_ros_py/setup.py | 2 +- yolox_ros_py/yolox_ros_py/yolox_onnx.py | 5 +---- yolox_ros_py/yolox_ros_py/yolox_openvino.py | 9 +-------- yolox_ros_py/yolox_ros_py/yolox_ros.py | 8 +------- yolox_ros_py/yolox_ros_py/yolox_tflite.py | 7 +------ 7 files changed, 7 insertions(+), 28 deletions(-) diff --git a/README.md b/README.md index c009840..e099ad3 100644 --- a/README.md +++ b/README.md @@ -124,7 +124,7 @@ Check [this URL](https://github.com/Ar-Ray-code/YOLOX-ROS/tree/main/yolox_ros_cp -- yololx/bounding_boxes : Output BoundingBoxes like darknet_ros_msgs (`bboxes_ex_msgs/BoundingBoxes`) +- bounding_boxes: Output BoundingBoxes like darknet_ros_msgs (`bboxes_ex_msgs/BoundingBoxes`) ※ If you want to use `darknet_ros_msgs` , replace `bboxes_ex_msgs` with `darknet_ros_msgs`. diff --git a/yolox_ros_py/package.xml b/yolox_ros_py/package.xml index b681fa3..da8bc3f 100755 --- a/yolox_ros_py/package.xml +++ b/yolox_ros_py/package.xml @@ -2,7 +2,7 @@ yolox_ros_py - 0.3.0 + 0.3.1 The yolox_ros_py package Ar-Ray-code Apache License, Version 2.0 diff --git a/yolox_ros_py/setup.py b/yolox_ros_py/setup.py index be111a1..000b167 100755 --- a/yolox_ros_py/setup.py +++ b/yolox_ros_py/setup.py @@ -77,7 +77,7 @@ setup( name=package_name, - version='0.3.0', + version='0.3.1', packages=[package_name], data_files=[ ('share/ament_index/resource_index/packages', diff --git a/yolox_ros_py/yolox_ros_py/yolox_onnx.py b/yolox_ros_py/yolox_ros_py/yolox_onnx.py index 4c24c21..576f7b2 100644 --- a/yolox_ros_py/yolox_ros_py/yolox_onnx.py +++ b/yolox_ros_py/yolox_ros_py/yolox_onnx.py @@ -44,9 +44,7 @@ def __init__(self) -> None: self.bridge = CvBridge() - self.pub = self.create_publisher(BoundingBoxes,"yolox/bounding_boxes", 10) - # self.pub_image = self.create_publisher(Image,"yolox/image_raw", 10) - + self.pub = self.create_publisher(BoundingBoxes,"bounding_boxes", 10) self.sub = self.create_subscription(Image,"image_raw",self.imageflow_callback, self.qos_image_sub) def imageflow_callback(self,msg:Image) -> None: @@ -99,7 +97,6 @@ def imageflow_callback(self,msg:Image) -> None: cv2.waitKey(1) self.pub.publish(bboxes) - # self.pub_image.publish(self.bridge.cv2_to_imgmsg(origin_img,"bgr8")) except Exception as e: self.get_logger().info(f'Error: {e}') diff --git a/yolox_ros_py/yolox_ros_py/yolox_openvino.py b/yolox_ros_py/yolox_ros_py/yolox_openvino.py index a12e3c0..31f8106 100644 --- a/yolox_ros_py/yolox_ros_py/yolox_openvino.py +++ b/yolox_ros_py/yolox_ros_py/yolox_openvino.py @@ -46,16 +46,10 @@ def __init__(self) -> None: self.bridge = CvBridge() - self.pub = self.create_publisher(BoundingBoxes,"yolox/bounding_boxes", 10) - # self.pub_image = self.create_publisher(Image,"yolox/image_raw", 10) - + self.pub = self.create_publisher(BoundingBoxes,"bounding_boxes", 10) self.sub = self.create_subscription(Image,"image_raw",self.imageflow_callback, self.qos_image_sub) def setting_yolox_exp(self) -> None: - # set environment variables for distributed training - - - print('Creating Inference Engine') ie = IECore() print(f'Reading the self.network: {self.model_path}') @@ -131,7 +125,6 @@ def imageflow_callback(self,msg:Image) -> None: cv2.waitKey(1) self.pub.publish(bboxes) - # self.pub_image.publish(self.bridge.cv2_to_imgmsg(nodetect_image,"bgr8")) except Exception as e: self.get_logger().info(f'Error: {e}') diff --git a/yolox_ros_py/yolox_ros_py/yolox_ros.py b/yolox_ros_py/yolox_ros_py/yolox_ros.py index 3f62dd7..faec75c 100644 --- a/yolox_ros_py/yolox_ros_py/yolox_ros.py +++ b/yolox_ros_py/yolox_ros_py/yolox_ros.py @@ -124,8 +124,7 @@ def __init__(self) -> None: self.bridge = CvBridge() - self.pub = self.create_publisher(BoundingBoxes,"yolox/bounding_boxes", 10) - # self.pub_image = self.create_publisher(Image,"yolox/image_raw", 10) + self.pub = self.create_publisher(BoundingBoxes,"bounding_boxes", 10) if (self.sensor_qos_mode): self.sub = self.create_subscription(Image,"image_raw",self.imageflow_callback, qos_profile_sensor_data) @@ -133,8 +132,6 @@ def __init__(self) -> None: self.sub = self.create_subscription(Image,"image_raw",self.imageflow_callback, 10) def setting_yolox_exp(self) -> None: - # set environment variables for distributed training - # ============================================================== WEIGHTS_PATH = '../../weights/yolox_nano.pth' @@ -245,9 +242,6 @@ def imageflow_callback(self,msg:Image) -> None: bboxes_msg = self.yolox2bboxes_msgs(bboxes, scores, cls, cls_names, msg.header, img_rgb) self.pub.publish(bboxes_msg) - # msg = self.bridge.cv2_to_imgmsg(img_rgb,"bgr8") - # msg.header.frame_id = "camera" - # self.pub_image.publish(msg) if (self.imshow_isshow): cv2.imshow("YOLOX",result_img_rgb) diff --git a/yolox_ros_py/yolox_ros_py/yolox_tflite.py b/yolox_ros_py/yolox_ros_py/yolox_tflite.py index 4001e66..73f1e00 100644 --- a/yolox_ros_py/yolox_ros_py/yolox_tflite.py +++ b/yolox_ros_py/yolox_ros_py/yolox_tflite.py @@ -54,12 +54,7 @@ def __init__(self): ) self.sub = self.create_subscription(Image,"image_raw",self.imageflow_callback, self.qos_image_sub) - - self.pub_detection = self.create_publisher( - BoundingBoxes, - 'bounding_boxes', - 10 - ) + self.pub_detection = self.create_publisher(BoundingBoxes, 'bounding_boxes', 10) def imageflow_callback(self, msg): start = time.time()