imagesift.cpp
Go to the documentation of this file.
1 // -*- c-basic-offset: 4; indent-tabs-mode: nil; -*-
2 // vim: tabstop=4 shiftwidth=4:
3 // Copyright (C) 2008 Rosen Diankov (rdiankov@cs.cmu.edu)
4 //
5 // This program is free software: you can redistribute it and/or modify
6 // it under the terms of the GNU Lesser General Public License as published by
7 // the Free Software Foundation, either version 3 of the License, or
8 // at your option) any later version.
9 //
10 // This program is distributed in the hope that it will be useful,
11 // but WITHOUT ANY WARRANTY; without even the implied warranty of
12 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
13 // GNU Lesser General Public License for more details.
14 //
15 // You should have received a copy of the GNU Lesser General Public License
16 // along with this program. If not, see <http://www.gnu.org/licenses/>.
17 #include "imagesift/imagesift.h"
18 #include <ros/node_handle.h>
19 #include <sensor_msgs/Image.h>
20 #include <sensor_msgs/CameraInfo.h>
21 #include <posedetection_msgs/ImageFeature0D.h>
22 #include <posedetection_msgs/Feature0DDetect.h>
25 #if ( CV_MAJOR_VERSION >= 4)
26 #include <opencv2/highgui.hpp>
27 #else
28 #include <opencv/highgui.h>
29 #include <opencv/cv.h>
30 #endif
31 
32 #include <boost/shared_ptr.hpp>
33 #include <boost/thread/mutex.hpp>
34 #include <map>
35 #include <string>
36 #include <cstdio>
37 #include <vector>
38 
39 #include <cv_bridge/cv_bridge.h>
41 #include <siftfast/siftfast.h>
42 
47 
48 using namespace std;
49 using namespace ros;
50 
51 namespace imagesift
52 {
53  void SiftNode::onInit()
54  {
55  DiagnosticNodelet::onInit();
56  // First positional argument is the transport type
57  std::string transport;
58  pnh_->param("image_transport", transport, std::string("raw"));
59  ROS_INFO_STREAM("Using transport \"" << transport << "\" for " << pnh_->getNamespace());
60  _it.reset(new image_transport::ImageTransport(*nh_));
61  _hints = image_transport::TransportHints(transport, ros::TransportHints(), *pnh_);
62 
63  pnh_->param("use_mask", _useMask, false);
64 
65  _pubFeatures = advertise<posedetection_msgs::Feature0D>(*nh_, "Feature0D", 1);
66  _pubSift = advertise<posedetection_msgs::ImageFeature0D>(*nh_, "ImageFeature0D", 1);
67  _srvDetect = nh_->advertiseService("Feature0DDetect", &SiftNode::detectCb, this);
68  lasttime = ros::WallTime::now();
69  _bInfoInitialized = false;
70 
71  onInitPostProcess();
72  }
73 
74  void SiftNode::subscribe()
75  {
76  if (!_useMask) {
77  _subImage = _it->subscribe(nh_->resolveName("image"), 1, &SiftNode::imageCb, this, _hints);
78  }
79  else {
80  _subImageWithMask.subscribe(*nh_, "image", 1);
81  _subMask.subscribe(*nh_, "mask", 1);
82  _sync = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
83  _sync->connectInput(_subImageWithMask, _subMask);
84  _sync->registerCallback(boost::bind(&SiftNode::imageCb, this, _1, _2));
85  }
86  _subInfo = nh_->subscribe("camera_info", 1, &SiftNode::infoCb, this);
87  }
88 
89  void SiftNode::unsubscribe()
90  {
91  if (!_useMask) {
92  _subImage.shutdown();
93  }
94  else {
95  _subImageWithMask.unsubscribe();
96  _subMask.unsubscribe();
97  }
98  _subInfo.shutdown();
99  }
100 
101  void SiftNode::infoCb(const sensor_msgs::CameraInfoConstPtr& msg_ptr)
102  {
103  boost::mutex::scoped_lock lock(_mutex);
104  _sift_msg.info = *msg_ptr;
105  _bInfoInitialized = true;
106  }
107 
108  bool SiftNode::detectCb(posedetection_msgs::Feature0DDetect::Request& req,
109  posedetection_msgs::Feature0DDetect::Response& res)
110  {
111  return detect(res.features,req.image, sensor_msgs::Image::ConstPtr());
112  }
113 
114  bool SiftNode::detect(posedetection_msgs::Feature0D& features, const sensor_msgs::Image& imagemsg,
115  const sensor_msgs::Image::ConstPtr& mask_ptr)
116  {
117  boost::mutex::scoped_lock lock(_mutex);
118  Image imagesift = NULL;
119  cv::Rect region;
120  try {
121  cv::Mat image;
122  cv_bridge::CvImagePtr framefloat;
123 
124  if (!(framefloat = cv_bridge::toCvCopy(imagemsg, "mono8")) )
125  return false;
126 
127  if(imagesift != NULL && (imagesift->cols!=imagemsg.width || imagesift->rows!=imagemsg.height)) {
128  ROS_DEBUG("clear sift resources");
129  DestroyAllImages();
130  imagesift = NULL;
131  }
132 
133  image = framefloat->image;
134 
135  if (mask_ptr) {
136  cv::Mat mask = cv_bridge::toCvShare(mask_ptr, mask_ptr->encoding)->image;
138  ROS_DEBUG ("region x:%d y:%d width:%d height:%d", region.x, region.y, region.width, region.height);
139  if (region.width == 0 || region.height ==0) {
140  region = cv::Rect(0, 0, imagemsg.width, imagemsg.height);
141  }
142  image = image(region);
143  }
144  else {
145  region = cv::Rect(0, 0, imagemsg.width, imagemsg.height);
146  }
147 
148  if(imagesift == NULL)
149  imagesift = CreateImage(imagemsg.height,imagemsg.width);
150 
151  for(int i = 0; i < imagemsg.height; ++i) {
152  uint8_t* psrc = (uint8_t*)image.data+image.step*i;
153  float* pdst = imagesift->pixels+i*imagesift->stride;
154  for(int j = 0; j < imagemsg.width; ++j)
155  pdst[j] = (float)psrc[j]*(1.0f/255.0f);
156  //memcpy(imagesift->pixels+i*imagesift->stride,framefloat->imageData+framefloat->widthStep*i,imagemsg.width*sizeof(float));
157  }
158  }
159  catch (cv_bridge::Exception error) {
160  ROS_WARN("bad frame");
161  return false;
162  }
163 
164  // compute SIFT
165  ros::WallTime siftbasetime = ros::WallTime::now();
166  Keypoint keypts = GetKeypoints(imagesift);
167  // write the keys to the output
168  int numkeys = 0;
169  Keypoint key = keypts;
170  while(key) {
171  numkeys++;
172  key = key->next;
173  }
174 
175  // publish
176  features.header = imagemsg.header;
177  features.positions.resize(numkeys*2);
178  features.scales.resize(numkeys);
179  features.orientations.resize(numkeys);
180  features.confidences.resize(numkeys);
181  features.descriptors.resize(numkeys*128);
182  features.descriptor_dim = 128;
183  features.type = "libsiftfast";
184 
185  int index = 0;
186  key = keypts;
187  while(key) {
188 
189  for(int j = 0; j < 128; ++j)
190  features.descriptors[128*index+j] = key->descrip[j];
191 
192  features.positions[2*index+0] = key->col + region.x;
193  features.positions[2*index+1] = key->row + region.y;
194  features.scales[index] = key->scale;
195  features.orientations[index] = key->ori;
196  features.confidences[index] = 1.0; // SIFT has no confidence?
197 
198  key = key->next;
199  ++index;
200  }
201 
202  FreeKeypoints(keypts);
203  DestroyAllImages();
204 
205  ROS_DEBUG("imagesift: image: %d(size=%lu), num: %d, sift time: %.3fs, total: %.3fs", imagemsg.header.seq,
206  imagemsg.data.size(), numkeys,
207  (float)(ros::WallTime::now()-siftbasetime).toSec(), (float)(ros::WallTime::now()-lasttime).toSec());
208  lasttime = ros::WallTime::now();
209  return true;
210  }
211 
212  void SiftNode::imageCb(const sensor_msgs::ImageConstPtr& msg_ptr,
213  const sensor_msgs::ImageConstPtr& mask_ptr)
214  {
215  vital_checker_->poke();
216  if(_pubFeatures.getNumSubscribers()==0 && _pubSift.getNumSubscribers()==0) {
217  ROS_DEBUG("number of subscribers is 0, ignoring image");
218  return;
219  }
220  detect(_sift_msg.features,*msg_ptr, mask_ptr);
221  _pubFeatures.publish(_sift_msg.features);
222 
223  if(!_bInfoInitialized) {
224  ROS_DEBUG("camera info not initialized, ignoring image");
225  return;
226  }
227  _sift_msg.image = *msg_ptr; // probably copying pointers so don't use after this call
228  {
229  boost::mutex::scoped_lock lock(_mutex); // needed for camerainfo
230  _pubSift.publish(_sift_msg);
231  }
232  }
233 
234  void SiftNode::imageCb(const sensor_msgs::ImageConstPtr& msg_ptr)
235  {
236  imageCb(msg_ptr, sensor_msgs::ImageConstPtr());
237  }
238 }
239 
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
f
void imageCb(const sensor_msgs::ImageConstPtr &msg)
#define ROS_WARN(...)
float
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
cv::Rect boundingRectOfMaskImage(const cv::Mat &image)
PLUGINLIB_EXPORT_CLASS(imagesift::SiftNode, nodelet::Nodelet)
#define ROS_INFO_STREAM(args)
static WallTime now()
#define ROS_DEBUG(...)


imagesift
Author(s): Rosen Diankov (rdiankov@cs.cmu.edu), Kei Okada
autogenerated on Mon May 3 2021 03:03:10