ros2/print_objects_detected_node.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2011-2014, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #include <rclcpp/rclcpp.hpp>
29 #include <find_object_2d/msg/objects_stamped.hpp>
32 #include <image_transport/image_transport.hpp>
33 #include <image_transport/subscriber_filter.hpp>
34 #include <cv_bridge/cv_bridge.h>
35 #include <opencv2/opencv.hpp>
36 #include <QTransform>
37 #include <QColor>
38 
39 class PrintObjects: public rclcpp::Node
40 {
41 public:
43  Node("objects_detected")
44  {
46 
47  imagePub_ = image_transport::create_publisher(this, "image_with_objects", rclcpp::QoS(1).reliability((rmw_qos_reliability_policy_t)1).get_rmw_qos_profile());
48 
49  // Simple subscriber
50  sub_ = create_subscription<std_msgs::msg::Float32MultiArray>("objects", rclcpp::QoS(1).reliability((rmw_qos_reliability_policy_t)1), std::bind(&PrintObjects::objectsDetectedCallback, this, std::placeholders::_1));
51 
52  // Synchronized image + objects example
53  imageSub_.subscribe(this, "image", hints.getTransport(), rclcpp::QoS(1).reliability((rmw_qos_reliability_policy_t)1).get_rmw_qos_profile());
54  objectsSub_.subscribe(this, "objectsStamped", rclcpp::QoS(1).reliability((rmw_qos_reliability_policy_t)1).get_rmw_qos_profile());
55 
57  exactSync_->registerCallback(std::bind(&PrintObjects::imageObjectsDetectedCallback, this, std::placeholders::_1, std::placeholders::_2));
58  }
59 
60  virtual ~PrintObjects()
61  {
62  delete exactSync_;
63  }
64 
71  const std_msgs::msg::Float32MultiArray::ConstSharedPtr msg)
72  {
73  printf("---\n");
74  const std::vector<float> & data = msg->data;
75  if(data.size())
76  {
77  for(unsigned int i=0; i<data.size(); i+=12)
78  {
79  // get data
80  int id = (int)data[i];
81  float objectWidth = data[i+1];
82  float objectHeight = data[i+2];
83 
84  // Find corners Qt
85  QTransform qtHomography(data[i+3], data[i+4], data[i+5],
86  data[i+6], data[i+7], data[i+8],
87  data[i+9], data[i+10], data[i+11]);
88 
89  QPointF qtTopLeft = qtHomography.map(QPointF(0,0));
90  QPointF qtTopRight = qtHomography.map(QPointF(objectWidth,0));
91  QPointF qtBottomLeft = qtHomography.map(QPointF(0,objectHeight));
92  QPointF qtBottomRight = qtHomography.map(QPointF(objectWidth,objectHeight));
93 
94  printf("Object %d detected, Qt corners at (%f,%f) (%f,%f) (%f,%f) (%f,%f)\n",
95  id,
96  qtTopLeft.x(), qtTopLeft.y(),
97  qtTopRight.x(), qtTopRight.y(),
98  qtBottomLeft.x(), qtBottomLeft.y(),
99  qtBottomRight.x(), qtBottomRight.y());
100  }
101  }
102  else
103  {
104  printf("No objects detected.\n");
105  }
106  }
108  const sensor_msgs::msg::Image::ConstSharedPtr imageMsg,
109  const find_object_2d::msg::ObjectsStamped::ConstSharedPtr objectsMsg)
110  {
111  if(imagePub_.getNumSubscribers() > 0)
112  {
113  const std::vector<float> & data = objectsMsg->objects.data;
114  if(data.size())
115  {
116  for(unsigned int i=0; i<data.size(); i+=12)
117  {
118  // get data
119  int id = (int)data[i];
120  float objectWidth = data[i+1];
121  float objectHeight = data[i+2];
122 
123  // Find corners OpenCV
124  cv::Mat cvHomography(3, 3, CV_32F);
125  cvHomography.at<float>(0,0) = data[i+3];
126  cvHomography.at<float>(1,0) = data[i+4];
127  cvHomography.at<float>(2,0) = data[i+5];
128  cvHomography.at<float>(0,1) = data[i+6];
129  cvHomography.at<float>(1,1) = data[i+7];
130  cvHomography.at<float>(2,1) = data[i+8];
131  cvHomography.at<float>(0,2) = data[i+9];
132  cvHomography.at<float>(1,2) = data[i+10];
133  cvHomography.at<float>(2,2) = data[i+11];
134  std::vector<cv::Point2f> inPts, outPts;
135  inPts.push_back(cv::Point2f(0,0));
136  inPts.push_back(cv::Point2f(objectWidth,0));
137  inPts.push_back(cv::Point2f(objectWidth,objectHeight));
138  inPts.push_back(cv::Point2f(0,objectHeight));
139  inPts.push_back(cv::Point2f(objectWidth/2,objectHeight/2));
140  cv::perspectiveTransform(inPts, outPts, cvHomography);
141 
142  cv_bridge::CvImageConstPtr imageDepthPtr = cv_bridge::toCvShare(imageMsg);
143 
144  cv_bridge::CvImage img;
145  img = *imageDepthPtr;
146  std::vector<cv::Point2i> outPtsInt;
147  outPtsInt.push_back(outPts[0]);
148  outPtsInt.push_back(outPts[1]);
149  outPtsInt.push_back(outPts[2]);
150  outPtsInt.push_back(outPts[3]);
151  QColor color(QColor((Qt::GlobalColor)((id % 10 + 7)==Qt::yellow?Qt::darkYellow:(id % 10 + 7))));
152  cv::Scalar cvColor(color.red(), color.green(), color.blue());
153  cv::polylines(img.image, outPtsInt, true, cvColor, 3);
154  cv::Point2i center = outPts[4];
155  cv::putText(img.image, QString("(%1, %2)").arg(center.x).arg(center.y).toStdString(), center, cv::FONT_HERSHEY_SIMPLEX, 0.6, cvColor, 2);
156  cv::circle(img.image, center, 1, cvColor, 3);
158  }
159  }
160  }
161  }
162 
163 private:
165  sensor_msgs::msg::Image,
166  find_object_2d::msg::ObjectsStamped> MyExactSyncPolicy;
171  rclcpp::Subscription<std_msgs::msg::Float32MultiArray>::SharedPtr sub_;
172 
173 };
174 
175 
176 int main(int argc, char** argv)
177 {
178  rclcpp::init(argc, argv);
179  rclcpp::spin(std::make_shared<PrintObjects>());
180  rclcpp::shutdown();
181 
182  return 0;
183 }
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
image_transport::SubscriberFilter imageSub_
void objectsDetectedCallback(const std_msgs::msg::Float32MultiArray::ConstSharedPtr msg)
const std::string & getTransport() const
uint32_t getNumSubscribers() const
image_transport::Publisher imagePub_
void imageObjectsDetectedCallback(const sensor_msgs::msg::Image::ConstSharedPtr imageMsg, const find_object_2d::msg::ObjectsStamped::ConstSharedPtr objectsMsg)
int main(int argc, char **argv)
message_filters::Subscriber< find_object_2d::msg::ObjectsStamped > objectsSub_
sensor_msgs::ImagePtr toImageMsg() const
void publish(const sensor_msgs::Image &message) const
message_filters::Synchronizer< MyExactSyncPolicy > * exactSync_
void subscribe(ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const TransportHints &transport_hints=TransportHints())
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
message_filters::sync_policies::ExactTime< sensor_msgs::msg::Image, find_object_2d::msg::ObjectsStamped > MyExactSyncPolicy
rclcpp::Subscription< std_msgs::msg::Float32MultiArray >::SharedPtr sub_


find_object_2d
Author(s): Mathieu Labbe
autogenerated on Mon Dec 12 2022 03:20:09