37 #ifndef IMAGESIFT_SIFT_NODE_H_ 38 #define IMAGESIFT_SIFT_NODE_H_ 42 #include <sensor_msgs/Image.h> 43 #include <posedetection_msgs/ImageFeature0D.h> 44 #include <posedetection_msgs/Feature0DDetect.h> 48 #include <boost/shared_ptr.hpp> 49 #include <boost/thread/mutex.hpp> 52 #include <siftfast/siftfast.h> 88 void infoCb(
const sensor_msgs::CameraInfoConstPtr& msg_ptr);
89 bool detectCb(posedetection_msgs::Feature0DDetect::Request& req,
90 posedetection_msgs::Feature0DDetect::Response& res);
91 bool detect(posedetection_msgs::Feature0D& features,
92 const sensor_msgs::Image& imagemsg,
93 const sensor_msgs::Image::ConstPtr& mask_ptr);
94 void imageCb(
const sensor_msgs::ImageConstPtr& msg_ptr,
95 const sensor_msgs::ImageConstPtr& mask_ptr);
96 void imageCb(
const sensor_msgs::ImageConstPtr& msg_ptr);
message_filters::Subscriber< sensor_msgs::Image > _subMask
void infoCb(const sensor_msgs::CameraInfoConstPtr &msg_ptr)
ros::ServiceServer _srvDetect
posedetection_msgs::ImageFeature0D _sift_msg
ros::Publisher _pubFeatures
message_filters::Subscriber< sensor_msgs::Image > _subImageWithMask
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > _sync
bool detectCb(posedetection_msgs::Feature0DDetect::Request &req, posedetection_msgs::Feature0DDetect::Response &res)
image_transport::TransportHints _hints
message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image > SyncPolicy
virtual void unsubscribe()
image_transport::Subscriber _subImage
bool detect(posedetection_msgs::Feature0D &features, const sensor_msgs::Image &imagemsg, const sensor_msgs::Image::ConstPtr &mask_ptr)
boost::shared_ptr< image_transport::ImageTransport > _it
void imageCb(const sensor_msgs::ImageConstPtr &msg_ptr, const sensor_msgs::ImageConstPtr &mask_ptr)