Public Types | Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes
imagesift::SiftNode Class Reference

#include <imagesift.h>

Inheritance diagram for imagesift::SiftNode:
Inheritance graph
[legend]

List of all members.

Public Types

typedef
message_filters::sync_policies::ExactTime
< sensor_msgs::Image,
sensor_msgs::Image > 
SyncPolicy

Public Member Functions

 SiftNode ()

Public Attributes

ros::Time lasttime

Protected Member Functions

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, const sensor_msgs::ImageConstPtr &mask_ptr)
void imageCb (const sensor_msgs::ImageConstPtr &msg_ptr)
void infoCb (const sensor_msgs::CameraInfoConstPtr &msg_ptr)
virtual void onInit ()
virtual void subscribe ()
virtual void unsubscribe ()

Protected Attributes

bool _bInfoInitialized
boost::shared_ptr
< image_transport::ImageTransport
_it
boost::mutex _mutex
ros::Publisher _pubFeatures
ros::Publisher _pubSift
posedetection_msgs::ImageFeature0D _sift_msg
ros::ServiceServer _srvDetect
image_transport::Subscriber _subImage
message_filters::Subscriber
< sensor_msgs::Image > 
_subImageWithMask
ros::Subscriber _subInfo
message_filters::Subscriber
< sensor_msgs::Image > 
_subMask
boost::shared_ptr
< message_filters::Synchronizer
< SyncPolicy > > 
_sync
bool _useMask

Detailed Description

Definition at line 60 of file imagesift.h.


Member Typedef Documentation

typedef message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image > imagesift::SiftNode::SyncPolicy

Definition at line 65 of file imagesift.h.


Constructor & Destructor Documentation

Definition at line 67 of file imagesift.h.


Member Function Documentation

bool imagesift::SiftNode::detect ( posedetection_msgs::Feature0D &  features,
const sensor_msgs::Image &  imagemsg,
const sensor_msgs::Image::ConstPtr &  mask_ptr 
) [protected]

Definition at line 103 of file imagesift.cpp.

bool imagesift::SiftNode::detectCb ( posedetection_msgs::Feature0DDetect::Request &  req,
posedetection_msgs::Feature0DDetect::Response &  res 
) [protected]

Definition at line 97 of file imagesift.cpp.

void imagesift::SiftNode::imageCb ( const sensor_msgs::ImageConstPtr &  msg_ptr,
const sensor_msgs::ImageConstPtr &  mask_ptr 
) [protected]

Definition at line 201 of file imagesift.cpp.

void imagesift::SiftNode::imageCb ( const sensor_msgs::ImageConstPtr &  msg_ptr) [protected]

Definition at line 222 of file imagesift.cpp.

void imagesift::SiftNode::infoCb ( const sensor_msgs::CameraInfoConstPtr &  msg_ptr) [protected]

Definition at line 90 of file imagesift.cpp.

void imagesift::SiftNode::onInit ( ) [protected, virtual]

Reimplemented from jsk_topic_tools::DiagnosticNodelet.

Definition at line 49 of file imagesift.cpp.

void imagesift::SiftNode::subscribe ( ) [protected, virtual]

Implements jsk_topic_tools::ConnectionBasedNodelet.

Definition at line 63 of file imagesift.cpp.

void imagesift::SiftNode::unsubscribe ( ) [protected, virtual]

Implements jsk_topic_tools::ConnectionBasedNodelet.

Definition at line 78 of file imagesift.cpp.


Member Data Documentation

Definition at line 69 of file imagesift.h.

Definition at line 72 of file imagesift.h.

boost::mutex imagesift::SiftNode::_mutex [protected]

Definition at line 71 of file imagesift.h.

Definition at line 80 of file imagesift.h.

Definition at line 81 of file imagesift.h.

posedetection_msgs::ImageFeature0D imagesift::SiftNode::_sift_msg [protected]

Definition at line 82 of file imagesift.h.

Definition at line 78 of file imagesift.h.

Definition at line 73 of file imagesift.h.

Definition at line 75 of file imagesift.h.

Definition at line 79 of file imagesift.h.

Definition at line 76 of file imagesift.h.

Definition at line 77 of file imagesift.h.

Definition at line 70 of file imagesift.h.

Definition at line 66 of file imagesift.h.


The documentation for this class was generated from the following files:


imagesift
Author(s): Rosen Diankov (rdiankov@cs.cmu.edu), Kei Okada
autogenerated on Wed Sep 16 2015 04:36:33