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 <ros/ros.h>
29 #include <find_object_2d/ObjectsStamped.h>
34 #include <cv_bridge/cv_bridge.h>
35 #include <opencv2/opencv.hpp>
36 #include <QTransform>
37 #include <QColor>
38 
40 
47  const std_msgs::Float32MultiArrayConstPtr & msg)
48 {
49  printf("---\n");
50  const std::vector<float> & data = msg->data;
51  if(data.size())
52  {
53  for(unsigned int i=0; i<data.size(); i+=12)
54  {
55  // get data
56  int id = (int)data[i];
57  float objectWidth = data[i+1];
58  float objectHeight = data[i+2];
59 
60  // Find corners Qt
61  QTransform qtHomography(data[i+3], data[i+4], data[i+5],
62  data[i+6], data[i+7], data[i+8],
63  data[i+9], data[i+10], data[i+11]);
64 
65  QPointF qtTopLeft = qtHomography.map(QPointF(0,0));
66  QPointF qtTopRight = qtHomography.map(QPointF(objectWidth,0));
67  QPointF qtBottomLeft = qtHomography.map(QPointF(0,objectHeight));
68  QPointF qtBottomRight = qtHomography.map(QPointF(objectWidth,objectHeight));
69 
70  printf("Object %d detected, Qt corners at (%f,%f) (%f,%f) (%f,%f) (%f,%f)\n",
71  id,
72  qtTopLeft.x(), qtTopLeft.y(),
73  qtTopRight.x(), qtTopRight.y(),
74  qtBottomLeft.x(), qtBottomLeft.y(),
75  qtBottomRight.x(), qtBottomRight.y());
76  }
77  }
78  else
79  {
80  printf("No objects detected.\n");
81  }
82 }
84  const sensor_msgs::ImageConstPtr & imageMsg,
85  const find_object_2d::ObjectsStampedConstPtr & objectsMsg)
86 {
87  if(imagePub.getNumSubscribers() > 0)
88  {
89  const std::vector<float> & data = objectsMsg->objects.data;
90  if(data.size())
91  {
92  for(unsigned int i=0; i<data.size(); i+=12)
93  {
94  // get data
95  int id = (int)data[i];
96  float objectWidth = data[i+1];
97  float objectHeight = data[i+2];
98 
99  // Find corners OpenCV
100  cv::Mat cvHomography(3, 3, CV_32F);
101  cvHomography.at<float>(0,0) = data[i+3];
102  cvHomography.at<float>(1,0) = data[i+4];
103  cvHomography.at<float>(2,0) = data[i+5];
104  cvHomography.at<float>(0,1) = data[i+6];
105  cvHomography.at<float>(1,1) = data[i+7];
106  cvHomography.at<float>(2,1) = data[i+8];
107  cvHomography.at<float>(0,2) = data[i+9];
108  cvHomography.at<float>(1,2) = data[i+10];
109  cvHomography.at<float>(2,2) = data[i+11];
110  std::vector<cv::Point2f> inPts, outPts;
111  inPts.push_back(cv::Point2f(0,0));
112  inPts.push_back(cv::Point2f(objectWidth,0));
113  inPts.push_back(cv::Point2f(objectWidth,objectHeight));
114  inPts.push_back(cv::Point2f(0,objectHeight));
115  inPts.push_back(cv::Point2f(objectWidth/2,objectHeight/2));
116  cv::perspectiveTransform(inPts, outPts, cvHomography);
117 
118  cv_bridge::CvImageConstPtr imageDepthPtr = cv_bridge::toCvShare(imageMsg);
119 
120  cv_bridge::CvImage img;
121  img = *imageDepthPtr;
122  std::vector<cv::Point2i> outPtsInt;
123  outPtsInt.push_back(outPts[0]);
124  outPtsInt.push_back(outPts[1]);
125  outPtsInt.push_back(outPts[2]);
126  outPtsInt.push_back(outPts[3]);
127  QColor color(QColor((Qt::GlobalColor)((id % 10 + 7)==Qt::yellow?Qt::darkYellow:(id % 10 + 7))));
128  cv::Scalar cvColor(color.red(), color.green(), color.blue());
129  cv::polylines(img.image, outPtsInt, true, cvColor, 3);
130  cv::Point2i center = outPts[4];
131  cv::putText(img.image, QString("(%1, %2)").arg(center.x).arg(center.y).toStdString(), center, cv::FONT_HERSHEY_SIMPLEX, 0.6, cvColor, 2);
132  cv::circle(img.image, center, 1, cvColor, 3);
133  imagePub.publish(img.toImageMsg());
134  }
135  }
136  }
137 }
138 
140 
141 int main(int argc, char** argv)
142 {
143  ros::init(argc, argv, "objects_detected");
144 
145  ros::NodeHandle nh;
147 
148  // Simple subscriber
149  ros::Subscriber sub;
150  sub = nh.subscribe("objects", 1, objectsDetectedCallback);
151 
152  // Synchronized image + objects example
154  imageSub.subscribe(it, nh.resolveName("image"), 1);
156  objectsSub.subscribe(nh, "objectsStamped", 1);
157  message_filters::Synchronizer<MyExactSyncPolicy> exactSync(MyExactSyncPolicy(10), imageSub, objectsSub);
158  exactSync.registerCallback(boost::bind(&imageObjectsDetectedCallback, _1, _2));
159 
160  imagePub = it.advertise("image_with_objects", 1);
161 
162  ros::spin();
163 
164  return 0;
165 }
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
std::string resolveName(const std::string &name, bool remap=true) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
uint32_t getNumSubscribers() const
ROSCPP_DECL void spin(Spinner &spinner)
Connection registerCallback(C &callback)
void publish(const sensor_msgs::Image &message) const
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)
sensor_msgs::ImagePtr toImageMsg() const


find_object_2d
Author(s): Mathieu Labbe
autogenerated on Thu Jun 6 2019 19:22:26