imagesift.cpp
Go to the documentation of this file.
00001 // -*- c-basic-offset: 4; indent-tabs-mode: nil; -*-
00002 // vim: tabstop=4 shiftwidth=4:
00003 // Copyright (C) 2008 Rosen Diankov (rdiankov@cs.cmu.edu)
00004 //
00005 // This program is free software: you can redistribute it and/or modify
00006 // it under the terms of the GNU Lesser General Public License as published by
00007 // the Free Software Foundation, either version 3 of the License, or
00008 // at your option) any later version.
00009 //
00010 // This program is distributed in the hope that it will be useful,
00011 // but WITHOUT ANY WARRANTY; without even the implied warranty of
00012 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00013 // GNU Lesser General Public License for more details.
00014 //
00015 // You should have received a copy of the GNU Lesser General Public License
00016 // along with this program.  If not, see <http://www.gnu.org/licenses/>.
00017 #include "imagesift/imagesift.h"
00018 #include <ros/node_handle.h>
00019 #include <sensor_msgs/Image.h>
00020 #include <sensor_msgs/CameraInfo.h>
00021 #include <posedetection_msgs/ImageFeature0D.h>
00022 #include <posedetection_msgs/Feature0DDetect.h>
00023 #include <image_transport/image_transport.h>
00024 #include <image_transport/subscriber_filter.h>
00025 #include <opencv/highgui.h>
00026 #include <opencv/cv.h>
00027 
00028 #include <boost/shared_ptr.hpp>
00029 #include <boost/thread/mutex.hpp>
00030 #include <map>
00031 #include <string>
00032 #include <cstdio>
00033 #include <vector>
00034 
00035 #include <cv_bridge/cv_bridge.h>
00036 #include <sensor_msgs/image_encodings.h>
00037 #include <siftfast/siftfast.h>
00038 
00039 #include <message_filters/subscriber.h>
00040 #include <message_filters/time_synchronizer.h>
00041 #include <message_filters/synchronizer.h>
00042 #include <jsk_perception/image_utils.h>
00043 
00044 using namespace std;
00045 using namespace ros;
00046 
00047 namespace imagesift
00048 {
00049     void SiftNode::onInit()
00050     {
00051         DiagnosticNodelet::onInit();
00052         _it.reset(new image_transport::ImageTransport(*nh_));
00053 
00054         pnh_->param("use_mask", _useMask, false);
00055         
00056         _pubFeatures = advertise<posedetection_msgs::Feature0D>(*nh_, "Feature0D", 1);
00057         _pubSift = advertise<posedetection_msgs::ImageFeature0D>(*nh_, "ImageFeature0D", 1);
00058         _srvDetect = nh_->advertiseService("Feature0DDetect", &SiftNode::detectCb, this);
00059         lasttime = ros::Time::now();
00060         _bInfoInitialized = false;
00061     }
00062 
00063     void SiftNode::subscribe()
00064     {
00065         if (!_useMask) {
00066             _subImage = _it->subscribe("image", 1, &SiftNode::imageCb, this);
00067         }
00068         else {
00069             _subImageWithMask.subscribe(*nh_, "image", 1);
00070             _subMask.subscribe(*nh_, "mask", 1);
00071             _sync = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
00072             _sync->connectInput(_subImageWithMask, _subMask);
00073             _sync->registerCallback(boost::bind(&SiftNode::imageCb, this, _1, _2));
00074         }
00075         _subInfo = nh_->subscribe("camera_info", 1, &SiftNode::infoCb, this);
00076     }
00077 
00078     void SiftNode::unsubscribe()
00079     {
00080         if (!_useMask) {
00081             _subImage.shutdown();
00082         }
00083         else {
00084             _subImageWithMask.unsubscribe();
00085             _subMask.unsubscribe();
00086         }
00087         _subInfo.shutdown();
00088     }
00089 
00090     void SiftNode::infoCb(const sensor_msgs::CameraInfoConstPtr& msg_ptr)
00091     {
00092         boost::mutex::scoped_lock lock(_mutex);
00093         _sift_msg.info = *msg_ptr;
00094         _bInfoInitialized = true;
00095     }
00096 
00097     bool SiftNode::detectCb(posedetection_msgs::Feature0DDetect::Request& req,
00098                             posedetection_msgs::Feature0DDetect::Response& res)
00099     {
00100         return detect(res.features,req.image, sensor_msgs::Image::ConstPtr());
00101     }
00102 
00103     bool SiftNode::detect(posedetection_msgs::Feature0D& features, const sensor_msgs::Image& imagemsg,
00104                           const sensor_msgs::Image::ConstPtr& mask_ptr)
00105     {
00106         boost::mutex::scoped_lock lock(_mutex);
00107         Image imagesift = NULL;
00108         cv::Rect region;
00109         try {
00110             cv::Mat image;
00111             cv_bridge::CvImagePtr framefloat;
00112 
00113             if (!(framefloat = cv_bridge::toCvCopy(imagemsg, "mono8")) )
00114                 return false;
00115             
00116             if(imagesift != NULL && (imagesift->cols!=imagemsg.width || imagesift->rows!=imagemsg.height)) {
00117                 ROS_INFO("clear sift resources");
00118                 DestroyAllImages();
00119                 imagesift = NULL;
00120             }
00121             
00122             image = framefloat->image;
00123 
00124             if (mask_ptr) {
00125                 cv::Mat mask = cv_bridge::toCvShare(mask_ptr, mask_ptr->encoding)->image;
00126                 region = jsk_perception::boundingRectOfMaskImage(mask);
00127                 ROS_DEBUG ("region x:%d y:%d width:%d height:%d", region.x, region.y, region.width, region.height);
00128                 if (region.width == 0 || region.height ==0) {
00129                     region = cv::Rect(0, 0, imagemsg.width, imagemsg.height);
00130                 }
00131                 image = image(region);
00132             }
00133             else {
00134                 region = cv::Rect(0, 0, imagemsg.width, imagemsg.height);
00135             }
00136             
00137             if(imagesift == NULL)
00138                 imagesift = CreateImage(imagemsg.height,imagemsg.width);
00139 
00140             for(int i = 0; i < imagemsg.height; ++i) {
00141                 uint8_t* psrc = (uint8_t*)image.data+image.step*i;
00142                 float* pdst = imagesift->pixels+i*imagesift->stride;
00143                 for(int j = 0; j < imagemsg.width; ++j)
00144                     pdst[j] = (float)psrc[j]*(1.0f/255.0f);
00145                 //memcpy(imagesift->pixels+i*imagesift->stride,framefloat->imageData+framefloat->widthStep*i,imagemsg.width*sizeof(float));
00146             }
00147         }
00148         catch (cv_bridge::Exception error) {
00149             ROS_WARN("bad frame");
00150             return false;
00151         }
00152 
00153         // compute SIFT
00154         ros::Time siftbasetime = ros::Time::now();
00155         Keypoint keypts = GetKeypoints(imagesift);
00156         // write the keys to the output
00157         int numkeys = 0;
00158         Keypoint key = keypts;
00159         while(key) {
00160             numkeys++;
00161             key = key->next;
00162         }
00163 
00164         // publish
00165         features.header = imagemsg.header;
00166         features.positions.resize(numkeys*2);
00167         features.scales.resize(numkeys);
00168         features.orientations.resize(numkeys);
00169         features.confidences.resize(numkeys);
00170         features.descriptors.resize(numkeys*128);
00171         features.descriptor_dim = 128;
00172         features.type = "libsiftfast";
00173 
00174         int index = 0;
00175         key = keypts;
00176         while(key) {
00177 
00178             for(int j = 0; j < 128; ++j)
00179                 features.descriptors[128*index+j] = key->descrip[j];
00180 
00181             features.positions[2*index+0] = key->col + region.x;
00182             features.positions[2*index+1] = key->row + region.y;
00183             features.scales[index] = key->scale;
00184             features.orientations[index] = key->ori;
00185             features.confidences[index] = 1.0; // SIFT has no confidence?
00186 
00187             key = key->next;
00188             ++index;
00189         }
00190 
00191         FreeKeypoints(keypts);
00192         DestroyAllImages();
00193 
00194         ROS_INFO("imagesift: image: %d(size=%lu), num: %d, sift time: %.3fs, total: %.3fs", imagemsg.header.seq,
00195                  imagemsg.data.size(),  numkeys,
00196                  (float)(ros::Time::now()-siftbasetime).toSec(), (float)(ros::Time::now()-lasttime).toSec());
00197         lasttime = ros::Time::now();
00198         return true;
00199     }
00200 
00201     void SiftNode::imageCb(const sensor_msgs::ImageConstPtr& msg_ptr,
00202                            const sensor_msgs::ImageConstPtr& mask_ptr)
00203     {
00204         if(_pubFeatures.getNumSubscribers()==0 && _pubSift.getNumSubscribers()==0) {
00205             ROS_DEBUG("number of subscribers is 0, ignoring image");
00206             return;
00207         }
00208         detect(_sift_msg.features,*msg_ptr, mask_ptr);
00209         _pubFeatures.publish(_sift_msg.features);
00210 
00211         if(!_bInfoInitialized) {
00212             ROS_DEBUG("camera info not initialized, ignoring image");
00213             return;
00214         }
00215         _sift_msg.image = *msg_ptr; // probably copying pointers so don't use after this call
00216         {
00217             boost::mutex::scoped_lock lock(_mutex); // needed for camerainfo
00218             _pubSift.publish(_sift_msg);
00219         }
00220     }
00221     
00222     void SiftNode::imageCb(const sensor_msgs::ImageConstPtr& msg_ptr)
00223     {
00224         imageCb(msg_ptr, sensor_msgs::ImageConstPtr());
00225     }
00226 }
00227 
00228 #include <pluginlib/class_list_macros.h>
00229 PLUGINLIB_EXPORT_CLASS (imagesift::SiftNode, nodelet::Nodelet);


imagesift
Author(s): Rosen Diankov (rdiankov@cs.cmu.edu), Kei Okada
autogenerated on Wed Sep 16 2015 04:36:33