#include <ar_kinect.h>
Public Member Functions | |
| ARPublisher (ros::NodeHandle &n) | |
| ~ARPublisher (void) | |
Private Member Functions | |
| void | arInit () | 
| void | getTransformationCallback (const sensor_msgs::PointCloud2ConstPtr &) | 
Private Attributes | |
| ros::Publisher | arMarkerPub_ | 
| ar_pose::ARMarkers | arPoseMarkers_ | 
| tf::TransformBroadcaster | broadcaster_ | 
| ARParam | cam_param_ | 
| IplImage * | capture_ | 
| ros::Subscriber | cloud_sub_ | 
| ARMultiMarkerInfoT * | config | 
| bool | configured_ | 
| char | data_directory_ [FILENAME_MAX] | 
| bool | getCamInfo_ | 
| ros::NodeHandle | n_ | 
| ar_object::ObjectData_T * | object | 
| int | objectnum | 
| char | pattern_filename_ [FILENAME_MAX] | 
| bool | publishTf_ | 
| bool | publishVisualMarkers_ | 
| visualization_msgs::Marker | rvizMarker_ | 
| ros::Publisher | rvizMarkerPub_ | 
| CvSize | sz_ | 
| int | threshold_ | 
Definition at line 68 of file ar_kinect.h.
Definition at line 63 of file ar_kinect.cpp.
| ar_pose::ARPublisher::~ARPublisher | ( | void | ) | 
Definition at line 112 of file ar_kinect.cpp.
| void ar_pose::ARPublisher::arInit | ( | ) |  [private] | 
        
Definition at line 121 of file ar_kinect.cpp.
| void ar_pose::ARPublisher::getTransformationCallback | ( | const sensor_msgs::PointCloud2ConstPtr & | msg | ) |  [private] | 
        
Definition at line 140 of file ar_kinect.cpp.
Definition at line 81 of file ar_kinect.h.
ar_pose::ARMarkers ar_pose::ARPublisher::arPoseMarkers_ [private] | 
        
Definition at line 95 of file ar_kinect.h.
Definition at line 79 of file ar_kinect.h.
ARParam ar_pose::ARPublisher::cam_param_ [private] | 
        
Definition at line 88 of file ar_kinect.h.
IplImage* ar_pose::ARPublisher::capture_ [private] | 
        
Definition at line 101 of file ar_kinect.h.
Definition at line 80 of file ar_kinect.h.
ARMultiMarkerInfoT* ar_pose::ARPublisher::config [private] | 
        
Definition at line 89 of file ar_kinect.h.
bool ar_pose::ARPublisher::configured_ [private] | 
        
Definition at line 102 of file ar_kinect.h.
char ar_pose::ARPublisher::data_directory_[FILENAME_MAX] [private] | 
        
Definition at line 93 of file ar_kinect.h.
bool ar_pose::ARPublisher::getCamInfo_ [private] | 
        
Definition at line 97 of file ar_kinect.h.
ros::NodeHandle ar_pose::ARPublisher::n_ [private] | 
        
Definition at line 78 of file ar_kinect.h.
Definition at line 90 of file ar_kinect.h.
int ar_pose::ARPublisher::objectnum [private] | 
        
Definition at line 91 of file ar_kinect.h.
char ar_pose::ARPublisher::pattern_filename_[FILENAME_MAX] [private] | 
        
Definition at line 92 of file ar_kinect.h.
bool ar_pose::ARPublisher::publishTf_ [private] | 
        
Definition at line 98 of file ar_kinect.h.
bool ar_pose::ARPublisher::publishVisualMarkers_ [private] | 
        
Definition at line 99 of file ar_kinect.h.
visualization_msgs::Marker ar_pose::ARPublisher::rvizMarker_ [private] | 
        
Definition at line 85 of file ar_kinect.h.
Definition at line 84 of file ar_kinect.h.
CvSize ar_pose::ARPublisher::sz_ [private] | 
        
Definition at line 100 of file ar_kinect.h.
int ar_pose::ARPublisher::threshold_ [private] | 
        
Definition at line 96 of file ar_kinect.h.