|
| 1 | +// Copyright 2020 Tier IV, Inc. |
| 2 | +// |
| 3 | +// Licensed under the Apache License, Version 2.0 (the "License"); |
| 4 | +// you may not use this file except in compliance with the License. |
| 5 | +// You may obtain a copy of the License at |
| 6 | +// |
| 7 | +// http://www.apache.org/licenses/LICENSE-2.0 |
| 8 | +// |
| 9 | +// Unless required by applicable law or agreed to in writing, software |
| 10 | +// distributed under the License is distributed on an "AS IS" BASIS, |
| 11 | +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 12 | +// See the License for the specific language governing permissions and |
| 13 | +// limitations under the License. |
| 14 | + |
| 15 | +#ifndef ROI_CLUSTER_FUSION__ROI_CLUSTER_FUSION_NODELET_HPP_ |
| 16 | +#define ROI_CLUSTER_FUSION__ROI_CLUSTER_FUSION_NODELET_HPP_ |
| 17 | + |
| 18 | +#define EIGEN_MPL2_ONLY |
| 19 | + |
| 20 | +#include <Eigen/Core> |
| 21 | +#include <image_transport/image_transport.hpp> |
| 22 | +#include <rclcpp/rclcpp.hpp> |
| 23 | + |
| 24 | +#include <autoware_perception_msgs/msg/detected_objects_with_feature.hpp> |
| 25 | +#include <sensor_msgs/msg/camera_info.hpp> |
| 26 | + |
| 27 | +#include <boost/circular_buffer.hpp> |
| 28 | + |
| 29 | +#include <cv_bridge/cv_bridge.h> |
| 30 | +#include <message_filters/pass_through.h> |
| 31 | +#include <message_filters/subscriber.h> |
| 32 | +#include <message_filters/sync_policies/approximate_time.h> |
| 33 | +#include <message_filters/synchronizer.h> |
| 34 | +#include <tf2_ros/buffer.h> |
| 35 | +#include <tf2_ros/transform_listener.h> |
| 36 | + |
| 37 | +#include <map> |
| 38 | +#include <memory> |
| 39 | +#include <vector> |
| 40 | + |
| 41 | +namespace roi_cluster_fusion |
| 42 | +{ |
| 43 | +class Debugger |
| 44 | +{ |
| 45 | +public: |
| 46 | + explicit Debugger(rclcpp::Node * node, const int camera_num); |
| 47 | + ~Debugger() = default; |
| 48 | + rclcpp::Node * node_; |
| 49 | + void showImage( |
| 50 | + const int id, const rclcpp::Time & time, |
| 51 | + const std::vector<sensor_msgs::msg::RegionOfInterest> & image_rois, |
| 52 | + const std::vector<sensor_msgs::msg::RegionOfInterest> & pointcloud_rois, |
| 53 | + const std::vector<Eigen::Vector2d> & points); |
| 54 | + |
| 55 | +private: |
| 56 | + void imageCallback(const sensor_msgs::msg::Image::ConstSharedPtr & input_image_msg, const int id); |
| 57 | + std::shared_ptr<image_transport::ImageTransport> image_transport_; |
| 58 | + std::vector<image_transport::Subscriber> image_subs_; |
| 59 | + std::vector<image_transport::Publisher> image_pubs_; |
| 60 | + std::vector<boost::circular_buffer<sensor_msgs::msg::Image::ConstSharedPtr>> image_buffers_; |
| 61 | +}; |
| 62 | + |
| 63 | +class RoiClusterFusionNodelet : public rclcpp::Node |
| 64 | +{ |
| 65 | +public: |
| 66 | + explicit RoiClusterFusionNodelet(const rclcpp::NodeOptions & options); |
| 67 | + |
| 68 | +private: |
| 69 | + void fusionCallback( |
| 70 | + autoware_perception_msgs::msg::DetectedObjectsWithFeature::ConstSharedPtr input_cluster_msg, |
| 71 | + autoware_perception_msgs::msg::DetectedObjectsWithFeature::ConstSharedPtr input_roi0_msg, |
| 72 | + autoware_perception_msgs::msg::DetectedObjectsWithFeature::ConstSharedPtr input_roi1_msg, |
| 73 | + autoware_perception_msgs::msg::DetectedObjectsWithFeature::ConstSharedPtr input_roi2_msg, |
| 74 | + autoware_perception_msgs::msg::DetectedObjectsWithFeature::ConstSharedPtr input_roi3_msg, |
| 75 | + autoware_perception_msgs::msg::DetectedObjectsWithFeature::ConstSharedPtr input_roi4_msg, |
| 76 | + autoware_perception_msgs::msg::DetectedObjectsWithFeature::ConstSharedPtr input_roi5_msg, |
| 77 | + autoware_perception_msgs::msg::DetectedObjectsWithFeature::ConstSharedPtr input_roi6_msg, |
| 78 | + autoware_perception_msgs::msg::DetectedObjectsWithFeature::ConstSharedPtr input_roi7_msg); |
| 79 | + void cameraInfoCallback( |
| 80 | + const sensor_msgs::msg::CameraInfo::ConstSharedPtr input_camera_info_msg, const int id); |
| 81 | + double calcIoU( |
| 82 | + const sensor_msgs::msg::RegionOfInterest & roi_1, |
| 83 | + const sensor_msgs::msg::RegionOfInterest & roi_2); |
| 84 | + double calcIoUX( |
| 85 | + const sensor_msgs::msg::RegionOfInterest & roi_1, |
| 86 | + const sensor_msgs::msg::RegionOfInterest & roi_2); |
| 87 | + double calcIoUY( |
| 88 | + const sensor_msgs::msg::RegionOfInterest & roi_1, |
| 89 | + const sensor_msgs::msg::RegionOfInterest & roi_2); |
| 90 | + |
| 91 | + rclcpp::Publisher<autoware_perception_msgs::msg::DetectedObjectsWithFeature>::SharedPtr |
| 92 | + labeled_cluster_pub_; |
| 93 | + std::vector<rclcpp::Subscription<sensor_msgs::msg::CameraInfo>::SharedPtr> v_camera_info_sub_; |
| 94 | + tf2_ros::Buffer tf_buffer_; |
| 95 | + tf2_ros::TransformListener tf_listener_ptr_; |
| 96 | + message_filters::Subscriber<autoware_perception_msgs::msg::DetectedObjectsWithFeature> |
| 97 | + cluster_sub_; |
| 98 | + std::vector<std::shared_ptr< |
| 99 | + message_filters::Subscriber<autoware_perception_msgs::msg::DetectedObjectsWithFeature>>> |
| 100 | + v_roi_sub_; |
| 101 | + message_filters::PassThrough<autoware_perception_msgs::msg::DetectedObjectsWithFeature> |
| 102 | + passthrough_; |
| 103 | + typedef message_filters::sync_policies::ApproximateTime< |
| 104 | + autoware_perception_msgs::msg::DetectedObjectsWithFeature, |
| 105 | + autoware_perception_msgs::msg::DetectedObjectsWithFeature, |
| 106 | + autoware_perception_msgs::msg::DetectedObjectsWithFeature, |
| 107 | + autoware_perception_msgs::msg::DetectedObjectsWithFeature, |
| 108 | + autoware_perception_msgs::msg::DetectedObjectsWithFeature, |
| 109 | + autoware_perception_msgs::msg::DetectedObjectsWithFeature, |
| 110 | + autoware_perception_msgs::msg::DetectedObjectsWithFeature, |
| 111 | + autoware_perception_msgs::msg::DetectedObjectsWithFeature, |
| 112 | + autoware_perception_msgs::msg::DetectedObjectsWithFeature> |
| 113 | + SyncPolicy; |
| 114 | + typedef message_filters::Synchronizer<SyncPolicy> Sync; |
| 115 | + std::shared_ptr<Sync> sync_ptr_; |
| 116 | + inline void dummyCallback( |
| 117 | + autoware_perception_msgs::msg::DetectedObjectsWithFeature::ConstSharedPtr input) |
| 118 | + { |
| 119 | + auto dummy = input; |
| 120 | + passthrough_.add(dummy); |
| 121 | + } |
| 122 | + // ROS Parameters |
| 123 | + bool use_iou_x_; |
| 124 | + bool use_iou_y_; |
| 125 | + bool use_iou_; |
| 126 | + bool use_cluster_semantic_type_; |
| 127 | + double iou_threshold_; |
| 128 | + int rois_number_; |
| 129 | + std::map<int, sensor_msgs::msg::CameraInfo> m_camera_info_; |
| 130 | + std::shared_ptr<Debugger> debugger_; |
| 131 | +}; |
| 132 | + |
| 133 | +} // namespace roi_cluster_fusion |
| 134 | + |
| 135 | +#endif // ROI_CLUSTER_FUSION__ROI_CLUSTER_FUSION_NODELET_HPP_ |
0 commit comments