#include <feature0d_to_image.h>
Public Types | |
| typedef message_filters::sync_policies::ExactTime< sensor_msgs::Image, posedetection_msgs::Feature0D > | SyncPolicy |
Public Member Functions | |
| Feature0DToImage () | |
| void | imagefeature_cb (const posedetection_msgs::ImageFeature0DConstPtr &msg_ptr) |
| void | imagefeature_cb (const sensor_msgs::ImageConstPtr &image_msg, const posedetection_msgs::Feature0DConstPtr &feature_msg) |
| virtual | ~Feature0DToImage () |
Public Attributes | |
| ros::NodeHandle | _node |
| ros::Publisher | _pub |
| message_filters::Subscriber< posedetection_msgs::Feature0D > | _sub_feature |
| message_filters::Subscriber< sensor_msgs::Image > | _sub_image |
| ros::Subscriber | _sub_imagefeature |
| boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > | _sync |
Definition at line 97 of file feature0d_to_image.h.
| typedef message_filters::sync_policies::ExactTime< sensor_msgs::Image, posedetection_msgs::Feature0D > posedetection_msgs::Feature0DToImage::SyncPolicy |
Definition at line 106 of file feature0d_to_image.h.
| posedetection_msgs::Feature0DToImage::Feature0DToImage | ( | ) |
Definition at line 27 of file feature0d_to_image.cpp.
|
virtual |
Definition at line 40 of file feature0d_to_image.cpp.
| void posedetection_msgs::Feature0DToImage::imagefeature_cb | ( | const posedetection_msgs::ImageFeature0DConstPtr & | msg_ptr | ) |
Definition at line 59 of file feature0d_to_image.cpp.
| void posedetection_msgs::Feature0DToImage::imagefeature_cb | ( | const sensor_msgs::ImageConstPtr & | image_msg, |
| const posedetection_msgs::Feature0DConstPtr & | feature_msg | ||
| ) |
Definition at line 42 of file feature0d_to_image.cpp.
| ros::NodeHandle posedetection_msgs::Feature0DToImage::_node |
Definition at line 100 of file feature0d_to_image.h.
| ros::Publisher posedetection_msgs::Feature0DToImage::_pub |
Definition at line 101 of file feature0d_to_image.h.
| message_filters::Subscriber<posedetection_msgs::Feature0D> posedetection_msgs::Feature0DToImage::_sub_feature |
Definition at line 109 of file feature0d_to_image.h.
| message_filters::Subscriber<sensor_msgs::Image> posedetection_msgs::Feature0DToImage::_sub_image |
Definition at line 108 of file feature0d_to_image.h.
| ros::Subscriber posedetection_msgs::Feature0DToImage::_sub_imagefeature |
Definition at line 102 of file feature0d_to_image.h.
| boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > posedetection_msgs::Feature0DToImage::_sync |
Definition at line 107 of file feature0d_to_image.h.