29 #include <find_object_2d/ObjectsStamped.h> 35 #include <opencv2/opencv.hpp> 47 const std_msgs::Float32MultiArrayConstPtr & msg)
50 const std::vector<float> & data = msg->data;
53 for(
unsigned int i=0; i<data.size(); i+=12)
56 int id = (int)data[i];
57 float objectWidth = data[i+1];
58 float objectHeight = data[i+2];
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]);
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));
70 printf(
"Object %d detected, Qt corners at (%f,%f) (%f,%f) (%f,%f) (%f,%f)\n",
72 qtTopLeft.x(), qtTopLeft.y(),
73 qtTopRight.x(), qtTopRight.y(),
74 qtBottomLeft.x(), qtBottomLeft.y(),
75 qtBottomRight.x(), qtBottomRight.y());
80 printf(
"No objects detected.\n");
84 const sensor_msgs::ImageConstPtr & imageMsg,
85 const find_object_2d::ObjectsStampedConstPtr & objectsMsg)
89 const std::vector<float> & data = objectsMsg->objects.data;
92 for(
unsigned int i=0; i<data.size(); i+=12)
95 int id = (int)data[i];
96 float objectWidth = data[i+1];
97 float objectHeight = data[i+2];
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);
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);
141 int main(
int argc,
char** argv)
143 ros::init(argc, argv,
"objects_detected");
156 objectsSub.
subscribe(nh,
"objectsStamped", 1);
159 boost::placeholders::_1, boost::placeholders::_2));
161 imagePub = it.
advertise(
"image_with_objects", 1);
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
uint32_t getNumSubscribers() const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
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)
sensor_msgs::ImagePtr toImageMsg() const
Connection registerCallback(C &callback)
int main(int argc, char **argv)
std::string resolveName(const std::string &name, bool remap=true) const
void imageObjectsDetectedCallback(const sensor_msgs::ImageConstPtr &imageMsg, const find_object_2d::ObjectsStampedConstPtr &objectsMsg)
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)
image_transport::Publisher imagePub
void objectsDetectedCallback(const std_msgs::Float32MultiArrayConstPtr &msg)
message_filters::sync_policies::ExactTime< sensor_msgs::Image, find_object_2d::ObjectsStamped > MyExactSyncPolicy