Go to the documentation of this file.
37 #ifndef IMAGESIFT_SIFT_NODE_H_
38 #define IMAGESIFT_SIFT_NODE_H_
40 #include <jsk_topic_tools/diagnostic_nodelet.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>
63 class SiftNode:
public jsk_topic_tools::DiagnosticNodelet
70 SiftNode(): DiagnosticNodelet(
"SiftNode") {}
87 posedetection_msgs::ImageFeature0D
_sift_msg;
92 void infoCb(
const sensor_msgs::CameraInfoConstPtr& msg_ptr);
93 bool detectCb(posedetection_msgs::Feature0DDetect::Request& req,
94 posedetection_msgs::Feature0DDetect::Response& res);
95 bool detect(posedetection_msgs::Feature0D& features,
96 const sensor_msgs::Image& imagemsg,
97 const sensor_msgs::Image::ConstPtr& mask_ptr);
98 void imageCb(
const sensor_msgs::ImageConstPtr& msg_ptr,
99 const sensor_msgs::ImageConstPtr& mask_ptr);
100 void imageCb(
const sensor_msgs::ImageConstPtr& msg_ptr);
void imageCb(const sensor_msgs::ImageConstPtr &msg_ptr, const sensor_msgs::ImageConstPtr &mask_ptr)
void infoCb(const sensor_msgs::CameraInfoConstPtr &msg_ptr)
message_filters::Subscriber< sensor_msgs::Image > _subImageWithMask
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > _sync
boost::shared_ptr< image_transport::ImageTransport > _it
static boost::mutex _g_siftfast_mutex
message_filters::Subscriber< sensor_msgs::Image > _subMask
image_transport::TransportHints _hints
posedetection_msgs::ImageFeature0D _sift_msg
ros::Publisher _pubFeatures
bool detect(posedetection_msgs::Feature0D &features, const sensor_msgs::Image &imagemsg, const sensor_msgs::Image::ConstPtr &mask_ptr)
message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image > SyncPolicy
virtual void unsubscribe()
image_transport::Subscriber _subImage
ros::ServiceServer _srvDetect
bool detectCb(posedetection_msgs::Feature0DDetect::Request &req, posedetection_msgs::Feature0DDetect::Response &res)
imagesift
Author(s): Rosen Diankov (rdiankov@cs.cmu.edu), Kei Okada
autogenerated on Fri May 16 2025 03:11:08