|
3 | 3 | #include <cmath> |
4 | 4 | #include <chrono> |
5 | 5 |
|
6 | | -#include <image_transport/image_transport.hpp> |
7 | 6 | #include <cv_bridge/cv_bridge.hpp> |
| 7 | +#include <image_transport/image_transport.hpp> |
8 | 8 | #include <rclcpp/rclcpp.hpp> |
9 | 9 | #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> |
11 | 13 |
|
12 | 14 | #include "bboxes_ex_msgs/msg/bounding_box.hpp" |
13 | 15 | #include "bboxes_ex_msgs/msg/bounding_boxes.hpp" |
|
17 | 19 | #include "yolox_param/yolox_param.hpp" |
18 | 20 |
|
19 | 21 | namespace yolox_ros_cpp{ |
20 | | - |
21 | 22 | class YoloXNode : public rclcpp::Node |
22 | 23 | { |
23 | 24 | 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 &); |
25 | 32 |
|
26 | 33 | protected: |
27 | 34 | std::shared_ptr<yolox_parameters::ParamListener> param_listener_; |
28 | 35 | yolox_parameters::Params params_; |
29 | 36 | private: |
30 | | - void onInit(); |
31 | | - rclcpp::TimerBase::SharedPtr init_timer_; |
32 | | - |
33 | 37 | std::unique_ptr<yolox_cpp::AbcYoloX> yolox_; |
34 | 38 | std::vector<std::string> class_names_; |
35 | 39 |
|
| 40 | + rclcpp::TimerBase::SharedPtr init_timer_; |
36 | 41 | image_transport::Subscriber sub_image_; |
37 | | - void colorImageCallback(const sensor_msgs::msg::Image::ConstSharedPtr&); |
38 | 42 |
|
39 | 43 | rclcpp::Publisher<bboxes_ex_msgs::msg::BoundingBoxes>::SharedPtr pub_bboxes_; |
| 44 | + rclcpp::Publisher<vision_msgs::msg::Detection2DArray>::SharedPtr pub_detection2d_; |
40 | 45 | 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&); |
43 | 46 | }; |
44 | 47 | } |
0 commit comments