#include <imagesift.h>
|  | 
| bool | detect (posedetection_msgs::Feature0D &features, const sensor_msgs::Image &imagemsg, const sensor_msgs::Image::ConstPtr &mask_ptr) | 
|  | 
| bool | detectCb (posedetection_msgs::Feature0DDetect::Request &req, posedetection_msgs::Feature0DDetect::Response &res) | 
|  | 
| 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) | 
|  | 
| virtual void | onInit () | 
|  | 
| virtual void | subscribe () | 
|  | 
| virtual void | unsubscribe () | 
|  | 
Definition at line 95 of file imagesift.h.
 
◆ SyncPolicy
◆ SiftNode()
  
  | 
        
          | imagesift::SiftNode::SiftNode | ( |  | ) |  |  | inline | 
 
 
◆ ~SiftNode()
  
  | 
        
          | imagesift::SiftNode::~SiftNode | ( |  | ) |  |  | virtual | 
 
 
◆ detect()
  
  | 
        
          | bool imagesift::SiftNode::detect | ( | posedetection_msgs::Feature0D & | features, |  
          |  |  | const sensor_msgs::Image & | imagemsg, |  
          |  |  | const sensor_msgs::Image::ConstPtr & | mask_ptr |  
          |  | ) |  |  |  | protected | 
 
 
◆ detectCb()
  
  | 
        
          | bool imagesift::SiftNode::detectCb | ( | posedetection_msgs::Feature0DDetect::Request & | req, |  
          |  |  | posedetection_msgs::Feature0DDetect::Response & | res |  
          |  | ) |  |  |  | protected | 
 
 
◆ imageCb() [1/2]
  
  | 
        
          | void imagesift::SiftNode::imageCb | ( | const sensor_msgs::ImageConstPtr & | msg_ptr | ) |  |  | protected | 
 
 
◆ imageCb() [2/2]
  
  | 
        
          | void imagesift::SiftNode::imageCb | ( | const sensor_msgs::ImageConstPtr & | msg_ptr, |  
          |  |  | const sensor_msgs::ImageConstPtr & | mask_ptr |  
          |  | ) |  |  |  | protected | 
 
 
◆ infoCb()
  
  | 
        
          | void imagesift::SiftNode::infoCb | ( | const sensor_msgs::CameraInfoConstPtr & | msg_ptr | ) |  |  | protected | 
 
 
◆ onInit()
  
  | 
        
          | void imagesift::SiftNode::onInit | ( |  | ) |  |  | protectedvirtual | 
 
 
◆ subscribe()
  
  | 
        
          | void imagesift::SiftNode::subscribe | ( |  | ) |  |  | protectedvirtual | 
 
 
◆ unsubscribe()
  
  | 
        
          | void imagesift::SiftNode::unsubscribe | ( |  | ) |  |  | protectedvirtual | 
 
 
◆ _bInfoInitialized
  
  | 
        
          | bool imagesift::SiftNode::_bInfoInitialized |  | protected | 
 
 
◆ _hints
◆ _it
◆ _mutex
  
  | 
        
          | boost::mutex imagesift::SiftNode::_mutex |  | protected | 
 
 
◆ _pubFeatures
◆ _pubSift
◆ _sift_msg
  
  | 
        
          | posedetection_msgs::ImageFeature0D imagesift::SiftNode::_sift_msg |  | protected | 
 
 
◆ _srvDetect
◆ _subImage
◆ _subImageWithMask
◆ _subInfo
◆ _subMask
◆ _sync
◆ _useMask
  
  | 
        
          | bool imagesift::SiftNode::_useMask |  | protected | 
 
 
◆ lasttime
The documentation for this class was generated from the following files: