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> 28 #include <opencv/highgui.h> 29 #include <opencv/cv.h> 32 #include <boost/shared_ptr.hpp> 33 #include <boost/thread/mutex.hpp> 41 #include <siftfast/siftfast.h> 53 void SiftNode::onInit()
55 DiagnosticNodelet::onInit();
57 std::string transport;
58 pnh_->param(
"image_transport", transport, std::string(
"raw"));
59 ROS_INFO_STREAM(
"Using transport \"" << transport <<
"\" for " << pnh_->getNamespace());
63 pnh_->param(
"use_mask", _useMask,
false);
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);
69 _bInfoInitialized =
false;
74 void SiftNode::subscribe()
77 _subImage = _it->subscribe(nh_->resolveName(
"image"), 1, &SiftNode::imageCb,
this, _hints);
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));
86 _subInfo = nh_->subscribe(
"camera_info", 1, &SiftNode::infoCb,
this);
89 void SiftNode::unsubscribe()
95 _subImageWithMask.unsubscribe();
96 _subMask.unsubscribe();
101 void SiftNode::infoCb(
const sensor_msgs::CameraInfoConstPtr& msg_ptr)
103 boost::mutex::scoped_lock lock(_mutex);
104 _sift_msg.info = *msg_ptr;
105 _bInfoInitialized =
true;
108 bool SiftNode::detectCb(posedetection_msgs::Feature0DDetect::Request& req,
109 posedetection_msgs::Feature0DDetect::Response& res)
111 return detect(res.features,req.image, sensor_msgs::Image::ConstPtr());
114 bool SiftNode::detect(posedetection_msgs::Feature0D& features,
const sensor_msgs::Image& imagemsg,
115 const sensor_msgs::Image::ConstPtr& mask_ptr)
117 boost::mutex::scoped_lock lock(_mutex);
127 if(imagesift != NULL && (imagesift->cols!=imagemsg.width || imagesift->rows!=imagemsg.height)) {
133 image = framefloat->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);
142 image = image(region);
145 region = cv::Rect(0, 0, imagemsg.width, imagemsg.height);
148 if(imagesift == NULL)
149 imagesift = CreateImage(imagemsg.height,imagemsg.width);
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.0
f/255.0
f);
166 Keypoint keypts = GetKeypoints(imagesift);
169 Keypoint key = keypts;
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";
189 for(
int j = 0; j < 128; ++j)
190 features.descriptors[128*index+j] = key->descrip[j];
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;
202 FreeKeypoints(keypts);
205 ROS_DEBUG(
"imagesift: image: %d(size=%lu), num: %d, sift time: %.3fs, total: %.3fs", imagemsg.header.seq,
206 imagemsg.data.size(), numkeys,
212 void SiftNode::imageCb(
const sensor_msgs::ImageConstPtr& msg_ptr,
213 const sensor_msgs::ImageConstPtr& mask_ptr)
215 vital_checker_->poke();
216 if(_pubFeatures.getNumSubscribers()==0 && _pubSift.getNumSubscribers()==0) {
217 ROS_DEBUG(
"number of subscribers is 0, ignoring image");
220 detect(_sift_msg.features,*msg_ptr, mask_ptr);
221 _pubFeatures.publish(_sift_msg.features);
223 if(!_bInfoInitialized) {
224 ROS_DEBUG(
"camera info not initialized, ignoring image");
227 _sift_msg.image = *msg_ptr;
229 boost::mutex::scoped_lock lock(_mutex);
230 _pubSift.publish(_sift_msg);
234 void SiftNode::imageCb(
const sensor_msgs::ImageConstPtr& msg_ptr)
236 imageCb(msg_ptr, sensor_msgs::ImageConstPtr());
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
void imageCb(const sensor_msgs::ImageConstPtr &msg)
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)