@@ -66,6 +66,19 @@ IsDetected::IsDetected(const std::string & xml_tag_name, const BT::NodeConfigura
6666 getInput (" order" , order_);
6767 getInput (" max_depth" , max_depth_);
6868 getInput (" person_id" , person_id_);
69+ getInput (" pub_bb_img" , pub_bb_img_);
70+
71+ if (pub_bb_img_) {
72+ pub_bb_img_ = node_->create_publisher <sensor_msgs::msg::Image>(
73+ " /bb_img_best_detection" , 10 );
74+ img_sub_ = node_->create_subscription <sensor_msgs::msg::Image>(
75+ " /camera/color/image_raw" , 10 ,
76+ std::bind (&IsDetected::image_callback, this , _1));
77+ } else {
78+ pub_bb_img_ = nullptr ;
79+ img_sub_ = nullptr ;
80+ }
81+
6982}
7083
7184BT::NodeStatus IsDetected::tick ()
@@ -96,7 +109,7 @@ BT::NodeStatus IsDetected::tick()
96109 return BT::NodeStatus::FAILURE;
97110 }
98111
99- RCLCPP_DEBUG (node_->get_logger (), " [IsDetected] Processing %d detections..." , detections.size ());
112+ RCLCPP_DEBUG (node_->get_logger (), " [IsDetected] Processing %ld detections..." , detections.size ());
100113
101114 if (order_ == " color" ) {
102115 // sorted by the distance to the color person we should sort it by distance and also by left to right or right to left
@@ -220,12 +233,26 @@ BT::NodeStatus IsDetected::tick()
220233 RCLCPP_INFO (node_->get_logger (), " [IsDetected] %d detections after filter" , frames_.size ());
221234 }
222235
223- // auto pub = node_->create_publisher<sensor_msgs::msg::Image>(
224- // "/object_detected", 10);
236+
225237
226238 // pub->publish(detections[0].image);
227239
228240 setOutput (" best_detection" , detections[0 ].class_name );
241+
242+ if (pub_bb_img_) {
243+ cv::Point center2d (
244+ detections[0 ].center2d .x , detections[0 ].center2d .y );
245+
246+ // cv::circle(last_image_, center2d, 5, cv::Scalar(0, 0, 255), -1);
247+
248+ cv::putText (
249+ last_image_, " X" , center2d, cv::FONT_HERSHEY_SIMPLEX, 1 ,
250+ cv::Scalar (0 , 0 , 255 ), 2 );
251+
252+ auto msg = cv_bridge::CvImage (std_msgs::msg::Header (), " bgr8" , last_image_).toImageMsg ();
253+ pub_bb_img_->publish (*msg);
254+ }
255+
229256 RCLCPP_DEBUG (node_->get_logger (), " [IsDetected] Detections sorted" );
230257 // implement more sorting methods
231258
@@ -238,6 +265,17 @@ BT::NodeStatus IsDetected::tick()
238265 return BT::NodeStatus::SUCCESS;
239266}
240267
268+ void IsDetected::image_callback (const sensor_msgs::msg::Image::SharedPtr msg)
269+ {
270+ cv_bridge::CvImagePtr image_rgb_ptr;
271+ try {
272+ image_rgb_ptr = cv_bridge::toCvCopy (msg->source_img , sensor_msgs::image_encodings::BGR8);
273+ } catch (cv_bridge::Exception & e) {
274+ RCLCPP_ERROR (get_logger (), " cv_bridge exception: %s" , e.what ());
275+ return ;
276+ }
277+ last_image_ = image_rgb_ptr->image ;
278+
241279} // namespace perception
242280
243281BT_REGISTER_NODES (factory) {
0 commit comments