00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
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_recognition_utils/cv_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::WallTime::now();
00060 _bInfoInitialized = false;
00061
00062 onInitPostProcess();
00063 }
00064
00065 void SiftNode::subscribe()
00066 {
00067 if (!_useMask) {
00068 _subImage = _it->subscribe("image", 1, &SiftNode::imageCb, this);
00069 }
00070 else {
00071 _subImageWithMask.subscribe(*nh_, "image", 1);
00072 _subMask.subscribe(*nh_, "mask", 1);
00073 _sync = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
00074 _sync->connectInput(_subImageWithMask, _subMask);
00075 _sync->registerCallback(boost::bind(&SiftNode::imageCb, this, _1, _2));
00076 }
00077 _subInfo = nh_->subscribe("camera_info", 1, &SiftNode::infoCb, this);
00078 }
00079
00080 void SiftNode::unsubscribe()
00081 {
00082 if (!_useMask) {
00083 _subImage.shutdown();
00084 }
00085 else {
00086 _subImageWithMask.unsubscribe();
00087 _subMask.unsubscribe();
00088 }
00089 _subInfo.shutdown();
00090 }
00091
00092 void SiftNode::infoCb(const sensor_msgs::CameraInfoConstPtr& msg_ptr)
00093 {
00094 boost::mutex::scoped_lock lock(_mutex);
00095 _sift_msg.info = *msg_ptr;
00096 _bInfoInitialized = true;
00097 }
00098
00099 bool SiftNode::detectCb(posedetection_msgs::Feature0DDetect::Request& req,
00100 posedetection_msgs::Feature0DDetect::Response& res)
00101 {
00102 return detect(res.features,req.image, sensor_msgs::Image::ConstPtr());
00103 }
00104
00105 bool SiftNode::detect(posedetection_msgs::Feature0D& features, const sensor_msgs::Image& imagemsg,
00106 const sensor_msgs::Image::ConstPtr& mask_ptr)
00107 {
00108 boost::mutex::scoped_lock lock(_mutex);
00109 Image imagesift = NULL;
00110 cv::Rect region;
00111 try {
00112 cv::Mat image;
00113 cv_bridge::CvImagePtr framefloat;
00114
00115 if (!(framefloat = cv_bridge::toCvCopy(imagemsg, "mono8")) )
00116 return false;
00117
00118 if(imagesift != NULL && (imagesift->cols!=imagemsg.width || imagesift->rows!=imagemsg.height)) {
00119 ROS_DEBUG("clear sift resources");
00120 DestroyAllImages();
00121 imagesift = NULL;
00122 }
00123
00124 image = framefloat->image;
00125
00126 if (mask_ptr) {
00127 cv::Mat mask = cv_bridge::toCvShare(mask_ptr, mask_ptr->encoding)->image;
00128 region = jsk_recognition_utils::boundingRectOfMaskImage(mask);
00129 ROS_DEBUG ("region x:%d y:%d width:%d height:%d", region.x, region.y, region.width, region.height);
00130 if (region.width == 0 || region.height ==0) {
00131 region = cv::Rect(0, 0, imagemsg.width, imagemsg.height);
00132 }
00133 image = image(region);
00134 }
00135 else {
00136 region = cv::Rect(0, 0, imagemsg.width, imagemsg.height);
00137 }
00138
00139 if(imagesift == NULL)
00140 imagesift = CreateImage(imagemsg.height,imagemsg.width);
00141
00142 for(int i = 0; i < imagemsg.height; ++i) {
00143 uint8_t* psrc = (uint8_t*)image.data+image.step*i;
00144 float* pdst = imagesift->pixels+i*imagesift->stride;
00145 for(int j = 0; j < imagemsg.width; ++j)
00146 pdst[j] = (float)psrc[j]*(1.0f/255.0f);
00147
00148 }
00149 }
00150 catch (cv_bridge::Exception error) {
00151 ROS_WARN("bad frame");
00152 return false;
00153 }
00154
00155
00156 ros::WallTime siftbasetime = ros::WallTime::now();
00157 Keypoint keypts = GetKeypoints(imagesift);
00158
00159 int numkeys = 0;
00160 Keypoint key = keypts;
00161 while(key) {
00162 numkeys++;
00163 key = key->next;
00164 }
00165
00166
00167 features.header = imagemsg.header;
00168 features.positions.resize(numkeys*2);
00169 features.scales.resize(numkeys);
00170 features.orientations.resize(numkeys);
00171 features.confidences.resize(numkeys);
00172 features.descriptors.resize(numkeys*128);
00173 features.descriptor_dim = 128;
00174 features.type = "libsiftfast";
00175
00176 int index = 0;
00177 key = keypts;
00178 while(key) {
00179
00180 for(int j = 0; j < 128; ++j)
00181 features.descriptors[128*index+j] = key->descrip[j];
00182
00183 features.positions[2*index+0] = key->col + region.x;
00184 features.positions[2*index+1] = key->row + region.y;
00185 features.scales[index] = key->scale;
00186 features.orientations[index] = key->ori;
00187 features.confidences[index] = 1.0;
00188
00189 key = key->next;
00190 ++index;
00191 }
00192
00193 FreeKeypoints(keypts);
00194 DestroyAllImages();
00195
00196 ROS_DEBUG("imagesift: image: %d(size=%lu), num: %d, sift time: %.3fs, total: %.3fs", imagemsg.header.seq,
00197 imagemsg.data.size(), numkeys,
00198 (float)(ros::WallTime::now()-siftbasetime).toSec(), (float)(ros::WallTime::now()-lasttime).toSec());
00199 lasttime = ros::WallTime::now();
00200 return true;
00201 }
00202
00203 void SiftNode::imageCb(const sensor_msgs::ImageConstPtr& msg_ptr,
00204 const sensor_msgs::ImageConstPtr& mask_ptr)
00205 {
00206 vital_checker_->poke();
00207 if(_pubFeatures.getNumSubscribers()==0 && _pubSift.getNumSubscribers()==0) {
00208 ROS_DEBUG("number of subscribers is 0, ignoring image");
00209 return;
00210 }
00211 detect(_sift_msg.features,*msg_ptr, mask_ptr);
00212 _pubFeatures.publish(_sift_msg.features);
00213
00214 if(!_bInfoInitialized) {
00215 ROS_DEBUG("camera info not initialized, ignoring image");
00216 return;
00217 }
00218 _sift_msg.image = *msg_ptr;
00219 {
00220 boost::mutex::scoped_lock lock(_mutex);
00221 _pubSift.publish(_sift_msg);
00222 }
00223 }
00224
00225 void SiftNode::imageCb(const sensor_msgs::ImageConstPtr& msg_ptr)
00226 {
00227 imageCb(msg_ptr, sensor_msgs::ImageConstPtr());
00228 }
00229 }
00230
00231 #include <pluginlib/class_list_macros.h>
00232 PLUGINLIB_EXPORT_CLASS (imagesift::SiftNode, nodelet::Nodelet);