Skip to content

Commit

Permalink
Merge pull request #22 from Ar-Ray-code/feature/yolox_py_update
Browse files Browse the repository at this point in the history
Feature/yolox py update (v0.3.1)
  • Loading branch information
Ar-Ray-code authored May 9, 2022
2 parents 1ca9482 + 5989847 commit 3f50e35
Show file tree
Hide file tree
Showing 16 changed files with 213 additions and 313 deletions.
8 changes: 4 additions & 4 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -10,9 +10,9 @@

| Base | ROS2 C++ | ROS2 Python |
| --------------- | -------- | ----------- |
| CPU | ||
| CUDA | ||
| CUDA (FP16) | ||
| PyTorch | ||
| PyTorch(CUDA) | ||
| PyTorch(CUDA-FP16) | ||
| TensorRT (CUDA) || |
| OpenVINO |||
| ONNX Runtime | ||
Expand Down Expand Up @@ -124,7 +124,7 @@ Check [this URL](https://github.com/Ar-Ray-code/YOLOX-ROS/tree/main/yolox_ros_cp

<!-- - yolox/image_raw : Resized image (`sensor_msgs/Image`) -->

- 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`.

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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},

Expand Down
3 changes: 0 additions & 3 deletions yolox_ros_py/launch/yolox_nano_onnx_gazebo.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -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},

Expand Down
55 changes: 55 additions & 0 deletions yolox_ros_py/launch/yolox_nano_onnx_picture.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,55 @@
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=[
{"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
])
4 changes: 0 additions & 4 deletions yolox_ros_py/launch/yolox_nano_onnx_youtube.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -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')
Expand Down Expand Up @@ -37,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},

Expand Down
2 changes: 0 additions & 2 deletions yolox_ros_py/launch/yolox_nano_openvino.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -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},
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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},
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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')

Expand All @@ -29,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},
Expand Down
2 changes: 1 addition & 1 deletion yolox_ros_py/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>yolox_ros_py</name>
<version>0.3.0</version>
<version>0.3.1</version>
<description>The yolox_ros_py package</description>
<maintainer email="ray255ar@gmail.com">Ar-Ray-code</maintainer>
<license>Apache License, Version 2.0</license>
Expand Down
2 changes: 1 addition & 1 deletion yolox_ros_py/setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -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',
Expand Down
100 changes: 12 additions & 88 deletions yolox_ros_py/yolox_ros_py/yolox_onnx.py
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -31,100 +33,26 @@
# 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")

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.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.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:
try:
# fps start
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)
Expand All @@ -145,39 +73,35 @@ 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"))

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()
Expand All @@ -189,6 +113,6 @@ def ros_main(args = None):
finally:
ros_class.destroy_node()
rclpy.shutdown()

if __name__ == "__main__":
ros_main()
Loading

0 comments on commit 3f50e35

Please sign in to comment.