Skip to content

Commit 55a2b13

Browse files
committed
update README
1 parent e70b07b commit 55a2b13

File tree

4 files changed

+19
-19
lines changed

4 files changed

+19
-19
lines changed

README.md

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -14,11 +14,10 @@ Japanese Reference (Plan to post):[Qiita](https://qiita.com/Ar-Ray)
1414
| Base | ROS1 C++ | ROS1 Python | ROS2 C++ | ROS2 Python |
1515
| ----------- | -------- | ----------- | -------- | ---------- |
1616
| MegEngine | | | | |
17-
| ONNXRuntime | | | | |
1817
| TensorRT | | | | |
1918
| CUDA | || ||
2019
| ncnn | | | | |
21-
| OpenVINO | | | | |
20+
| OpenVINO | | | | |
2221
| Others(?) | | | | |
2322

2423
## Requirements (Python)

weights/openvino/install.bash

Lines changed: 5 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -8,23 +8,24 @@ if [ -z "$1" ]; then
88
exit 1
99
fi
1010
MODEL=$1
11-
MO=/opt/intel/openvino_2021/deployment_tools/model_optimizer/mo.py
11+
MO=/opt/intel/openvino_2021/deployment_tools/model_optimizer/
1212
ROS2_WS=~/ros2_ws
1313

1414
rm -rf ~/openvino_download
1515
mkdir ~/openvino_download
1616
cd ~/openvino_download
1717
wget https://github.com/Megvii-BaseDetection/YOLOX/releases/download/0.1.1rc0/$MODEL.onnx
1818
# if $1==yolox_tiny or $1==yolox_nano
19+
cd $MO
1920
if [ "$MODEL" == "yolox_tiny" ] || [ "$MODEL" == "yolox_nano" ]; then
20-
python3 $MO --input_model ./$MODEL.onnx --input_shape [1,3,416,416] --data_type FP16 --output_dir ./
21+
python3 mo.py --input_model ~/openvino_download/$MODEL.onnx --input_shape [1,3,416,416] --data_type FP16 --output_dir ~/openvino_download/
2122
else
22-
python3 $MO --input_model ./$MODEL.onnx --input_shape [1,3,640,640] --data_type FP16 --output_dir ./
23+
python3 mo.py --input_model ~/openvino_download/$MODEL.onnx --input_shape [1,3,640,640] --data_type FP16 --output_dir ~/openvino_download/
2324
fi
2425
echo "=========================================="
2526
echo "Model Optimizer finished"
2627
echo "=========================================="
2728

28-
cp -r ./* $ROS2_WS/src/YOLOX-ROS/weights/openvino/
29+
cp -r ~/openvino_download/* $ROS2_WS/src/YOLOX-ROS/weights/openvino/
2930
cd $ROS2_WS
3031
colcon build --symlink-install

yolox_ros_py/launch/demo_yolox_openvino.launch.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,7 @@ def generate_launch_description():
1919
{"image_size/width": 640},
2020
{"image_size/height": 480},
2121
{"device" : 'CPU'},
22-
{"model_path" : yolox_ros_share_dir+"/yolox_m.xml"},
22+
{"model_path" : yolox_ros_share_dir+"/yolox_s.xml"},
2323
{"conf" : 0.3},
2424
],
2525
)

yolox_ros_py/yolox_ros_py/yolox_openvino.py

Lines changed: 12 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -70,9 +70,9 @@ def setting_yolox_exp(self) -> None:
7070
# =============================================================
7171
self.imshow_isshow = self.get_parameter('imshow_isshow').value
7272

73-
model_path = self.get_parameter('model_path').value
73+
self.model_path = self.get_parameter('model_path').value
7474
self.conf = self.get_parameter('conf').value
75-
device = self.get_parameter('device').value
75+
self.device = self.get_parameter('device').value
7676

7777
self.input_width = self.get_parameter('image_size/width').value
7878
self.input_height = self.get_parameter('image_size/height').value
@@ -81,10 +81,10 @@ def setting_yolox_exp(self) -> None:
8181

8282
print('Creating Inference Engine')
8383
ie = IECore()
84-
print(f'Reading the self.network: {model_path}')
84+
print(f'Reading the self.network: {self.model_path}')
8585
# (.xml and .bin files) or (.onnx file)
8686

87-
self.net = ie.read_network(model=model_path)
87+
self.net = ie.read_network(model=self.model_path)
8888
print('Configuring input and output blobs')
8989
# Get names of input and output blobs
9090
self.input_blob = next(iter(self.net.input_info))
@@ -94,11 +94,8 @@ def setting_yolox_exp(self) -> None:
9494
self.net.input_info[self.input_blob].precision = 'FP32'
9595
self.net.outputs[self.out_blob].precision = 'FP16'
9696

97-
# Get a number of classes recognized by a model
98-
num_of_classes = max(self.net.outputs[self.out_blob].shape)
99-
10097
print('Loading the model to the plugin')
101-
self.exec_net = ie.load_network(network=self.net, device_name=device)
98+
self.exec_net = ie.load_network(network=self.net, device_name=self.device)
10299

103100

104101
def yolox2bboxes_msgs(self, bboxes, scores, cls, cls_names, img_header:Header):
@@ -139,6 +136,7 @@ def imageflow_callback(self,msg:Image) -> None:
139136

140137
boxes = predictions[:, :4]
141138
scores = predictions[:, 4, None] * predictions[:, 5:]
139+
print(scores)
142140

143141
boxes_xyxy = np.ones_like(boxes)
144142
boxes_xyxy[:, 0] = boxes[:, 0] - boxes[:, 2]/2.
@@ -148,22 +146,23 @@ def imageflow_callback(self,msg:Image) -> None:
148146
boxes_xyxy /= ratio
149147
dets = multiclass_nms(boxes_xyxy, scores, nms_thr=0.45, score_thr=0.1)
150148

149+
print(dets)
151150
if dets is not None:
152151
final_boxes = dets[:, :4]
153152
final_scores, final_cls_inds = dets[:, 4], dets[:, 5]
154153
origin_img = vis(origin_img, final_boxes, final_scores, final_cls_inds,
155154
conf=self.conf, class_names=COCO_CLASSES)
155+
156156
# ==============================================================
157157
end_time = cv2.getTickCount()
158158
time_took = (end_time - start_time) / cv2.getTickFrequency()
159159

160160
# rclpy log FPS
161161
self.get_logger().info(f'FPS: {1 / time_took}')
162-
bboxes = self.yolox2bboxes_msgs(dets[:, :4], final_scores, final_cls_inds, COCO_CLASSES, msg.header)
163-
self.get_logger().info(f'bboxes: {bboxes}')
162+
164163
try:
165164
bboxes = self.yolox2bboxes_msgs(dets[:, :4], final_scores, final_cls_inds, COCO_CLASSES, msg.header)
166-
165+
self.get_logger().info(f'bboxes: {bboxes}')
167166
if (self.imshow_isshow):
168167
cv2.imshow("YOLOX",origin_img)
169168
cv2.waitKey(1)
@@ -177,7 +176,8 @@ def imageflow_callback(self,msg:Image) -> None:
177176
self.pub.publish(bboxes)
178177
self.pub_image.publish(self.bridge.cv2_to_imgmsg(img_rgb,"bgr8"))
179178

180-
except:
179+
except Exception as e:
180+
self.get_logger().info(f'Error: {e}')
181181
pass
182182

183183
# origin_img is output

0 commit comments

Comments
 (0)