Skip to content

Commit c1831f3

Browse files
committed
update yolox_cpp interface
1 parent 23755b9 commit c1831f3

File tree

5 files changed

+86
-25
lines changed

5 files changed

+86
-25
lines changed

yolox_ros_cpp/README.md

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -195,8 +195,7 @@ ros2 launch yolox_ros_cpp yolox_tflite.launch.py
195195
- See [here](https://github.com/fateshelled/YOLOX-ROS/blob/dev_cpp/yolox_ros_cpp/yolox_ros_cpp/labels/coco_names.txt) for label format.
196196
- `num_classes`: 80
197197
- `model_version`: 0.1.1rc0
198-
- `openvino/device`: CPU
199-
- `conf`: 0.3
198+
- `openvino/device`: AUTO
200199
- `nms`: 0.45
201200
- `imshow_isshow`: true
202201
- `src_image_topic_name`: /image_raw

yolox_ros_cpp/yolox_cpp/src/yolox_openvino.cpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,12 @@ namespace yolox_cpp{
1717
const auto network = ie.read_model(path_to_model);
1818

1919
// Step 3. Loading a model to the device
20+
std::vector<std::string> available_devices = ie.get_available_devices();
21+
std::cout << "======= AVAILABLE DEVICES FOR OPENVINO =======" << std::endl;
22+
for (auto device : available_devices) {
23+
std::cout << "- " << device << std::endl;
24+
}
25+
std::cout << "==============================================" << std::endl;
2026
std::cout << "Loading a model to the device: " << device_name_ << std::endl;
2127
auto compiled_model = ie.compile_model(network, device_name);
2228

yolox_ros_cpp/yolox_ros_cpp/include/yolox_ros_cpp/yolox_ros_cpp.hpp

Lines changed: 13 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -3,11 +3,13 @@
33
#include <cmath>
44
#include <chrono>
55

6+
#include <cv_bridge/cv_bridge.h>
67
#include <image_transport/image_transport.hpp>
7-
#include <cv_bridge/cv_bridge.hpp>
88
#include <rclcpp/rclcpp.hpp>
99
#include <rclcpp_components/register_node_macro.hpp>
10-
10+
#include <sensor_msgs/msg/image.hpp>
11+
#include <std_msgs/msg/header.hpp>
12+
#include <vision_msgs/msg/detection2_d_array.hpp>
1113

1214
#include "bboxes_ex_msgs/msg/bounding_box.hpp"
1315
#include "bboxes_ex_msgs/msg/bounding_boxes.hpp"
@@ -17,28 +19,29 @@
1719
#include "yolox_param/yolox_param.hpp"
1820

1921
namespace yolox_ros_cpp{
20-
2122
class YoloXNode : public rclcpp::Node
2223
{
2324
public:
24-
YoloXNode(const rclcpp::NodeOptions&);
25+
YoloXNode(const rclcpp::NodeOptions &);
26+
private:
27+
void onInit();
28+
void colorImageCallback(const sensor_msgs::msg::Image::ConstSharedPtr &);
29+
30+
static bboxes_ex_msgs::msg::BoundingBoxes objects_to_bboxes(const cv::Mat &, const std::vector<yolox_cpp::Object> &, const std_msgs::msg::Header &);
31+
static vision_msgs::msg::Detection2DArray objects_to_detection2d(const std::vector<yolox_cpp::Object> &, const std_msgs::msg::Header &);
2532

2633
protected:
2734
std::shared_ptr<yolox_parameters::ParamListener> param_listener_;
2835
yolox_parameters::Params params_;
2936
private:
30-
void onInit();
31-
rclcpp::TimerBase::SharedPtr init_timer_;
32-
3337
std::unique_ptr<yolox_cpp::AbcYoloX> yolox_;
3438
std::vector<std::string> class_names_;
3539

40+
rclcpp::TimerBase::SharedPtr init_timer_;
3641
image_transport::Subscriber sub_image_;
37-
void colorImageCallback(const sensor_msgs::msg::Image::ConstSharedPtr&);
3842

3943
rclcpp::Publisher<bboxes_ex_msgs::msg::BoundingBoxes>::SharedPtr pub_bboxes_;
44+
rclcpp::Publisher<vision_msgs::msg::Detection2DArray>::SharedPtr pub_detection2d_;
4045
image_transport::Publisher pub_image_;
41-
42-
bboxes_ex_msgs::msg::BoundingBoxes objects_to_bboxes(const cv::Mat&, const std::vector<yolox_cpp::Object>&, const std_msgs::msg::Header&);
4346
};
4447
}

yolox_ros_cpp/yolox_ros_cpp/package.xml

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -18,9 +18,12 @@
1818
<depend>std_msgs</depend>
1919
<depend>sensor_msgs</depend>
2020
<depend>bboxes_ex_msgs</depend>
21+
<depend>vision_msgs</depend>
2122
<depend>yolox_cpp</depend>
2223
<depend>yolox_param</depend>
2324

25+
<exec_depend>usb_cam</exec_depend>
26+
2427
<test_depend>ament_lint_auto</test_depend>
2528
<test_depend>ament_lint_common</test_depend>
2629

yolox_ros_cpp/yolox_ros_cpp/src/yolox_ros_cpp.cpp

Lines changed: 63 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -95,10 +95,20 @@ namespace yolox_ros_cpp
9595
this, this->params_.src_image_topic_name,
9696
std::bind(&YoloXNode::colorImageCallback, this, std::placeholders::_1),
9797
"raw");
98-
this->pub_bboxes_ = this->create_publisher<bboxes_ex_msgs::msg::BoundingBoxes>(
99-
this->params_.publish_boundingbox_topic_name,
100-
10);
101-
this->pub_image_ = image_transport::create_publisher(this, this->params_.publish_image_topic_name);
98+
99+
if (this->params_.use_bbox_ex_msgs) {
100+
this->pub_bboxes_ = this->create_publisher<bboxes_ex_msgs::msg::BoundingBoxes>(
101+
this->params_.publish_boundingbox_topic_name,
102+
10);
103+
} else {
104+
this->pub_detection2d_ = this->create_publisher<vision_msgs::msg::Detection2DArray>(
105+
this->params_.publish_boundingbox_topic_name,
106+
10);
107+
}
108+
109+
if (this->params_.publish_resized_image) {
110+
this->pub_image_ = image_transport::create_publisher(this, this->params_.publish_image_topic_name);
111+
}
102112
}
103113

104114
void YoloXNode::colorImageCallback(const sensor_msgs::msg::Image::ConstSharedPtr &ptr)
@@ -108,10 +118,10 @@ namespace yolox_ros_cpp
108118

109119
auto now = std::chrono::system_clock::now();
110120
auto objects = this->yolox_->inference(frame);
111-
112121
auto end = std::chrono::system_clock::now();
122+
113123
auto elapsed = std::chrono::duration_cast<std::chrono::milliseconds>(end - now);
114-
RCLCPP_INFO(this->get_logger(), "Inference: %f FPS", 1000.0f / elapsed.count());
124+
RCLCPP_INFO(this->get_logger(), "Inference time: %5ld ms", elapsed.count());
115125

116126
yolox_cpp::utils::draw_objects(frame, objects, this->class_names_);
117127
if (this->params_.imshow_isshow)
@@ -124,12 +134,32 @@ namespace yolox_ros_cpp
124134
}
125135
}
126136

127-
auto boxes = objects_to_bboxes(frame, objects, img->header);
128-
this->pub_bboxes_->publish(boxes);
137+
if (this->params_.use_bbox_ex_msgs)
138+
{
139+
if (this->pub_bboxes_ == nullptr)
140+
{
141+
RCLCPP_ERROR(this->get_logger(), "pub_bboxes_ is nullptr");
142+
return;
143+
}
144+
auto boxes = objects_to_bboxes(frame, objects, img->header);
145+
this->pub_bboxes_->publish(boxes);
146+
}
147+
else
148+
{
149+
if (this->pub_detection2d_ == nullptr)
150+
{
151+
RCLCPP_ERROR(this->get_logger(), "pub_detection2d_ is nullptr");
152+
return;
153+
}
154+
vision_msgs::msg::Detection2DArray detections = objects_to_detection2d(objects, img->header);
155+
this->pub_detection2d_->publish(detections);
156+
}
129157

130-
sensor_msgs::msg::Image::SharedPtr pub_img;
131-
pub_img = cv_bridge::CvImage(img->header, "bgr8", frame).toImageMsg();
132-
this->pub_image_.publish(pub_img);
158+
if (this->params_.publish_resized_image) {
159+
sensor_msgs::msg::Image::SharedPtr pub_img =
160+
cv_bridge::CvImage(img->header, "bgr8", frame).toImageMsg();
161+
this->pub_image_.publish(pub_img);
162+
}
133163
}
134164

135165
bboxes_ex_msgs::msg::BoundingBoxes YoloXNode::objects_to_bboxes(
@@ -140,8 +170,8 @@ namespace yolox_ros_cpp
140170
for (const auto &obj : objects)
141171
{
142172
bboxes_ex_msgs::msg::BoundingBox box;
143-
box.probability = obj.prob;
144-
box.class_id = this->class_names_[obj.label];
173+
box.probability = obj.prob;;
174+
box.class_id = std::to_string(obj.label);
145175
box.xmin = obj.rect.x;
146176
box.ymin = obj.rect.y;
147177
box.xmax = (obj.rect.x + obj.rect.width);
@@ -152,6 +182,26 @@ namespace yolox_ros_cpp
152182
}
153183
return boxes;
154184
}
185+
186+
vision_msgs::msg::Detection2DArray YoloXNode::objects_to_detection2d(const std::vector<yolox_cpp::Object> &objects, const std_msgs::msg::Header &header)
187+
{
188+
vision_msgs::msg::Detection2DArray detection2d;
189+
detection2d.header = header;
190+
for (const auto &obj : objects)
191+
{
192+
vision_msgs::msg::Detection2D det;
193+
det.bbox.center.position.x = obj.rect.x + obj.rect.width / 2;
194+
det.bbox.center.position.y = obj.rect.y + obj.rect.height / 2;
195+
det.bbox.size_x = obj.rect.width;
196+
det.bbox.size_y = obj.rect.height;
197+
198+
det.results.resize(1);
199+
det.results[0].hypothesis.class_id = std::to_string(obj.label);
200+
det.results[0].hypothesis.score = obj.prob;
201+
detection2d.detections.emplace_back(det);
202+
}
203+
return detection2d;
204+
}
155205
}
156206

157207
RCLCPP_COMPONENTS_REGISTER_NODE(yolox_ros_cpp::YoloXNode)

0 commit comments

Comments
 (0)