Public Member Functions | Private Types | Private Member Functions | Private Attributes
ARPublisher Class Reference

#include <ar_kinect.h>

List of all members.

Public Member Functions

 ARPublisher (ros::NodeHandle &n)
 ~ARPublisher (void)

Private Types

typedef boost::multi_array
< CoordinateFrame *, 3 > 
transform_type

Private Member Functions

void arInit ()
 Loads the patterns & initializes the lookup tables.
void camInfoCallback (const sensor_msgs::CameraInfoConstPtr &)
 Camera parameters callback.
void cloudCallback (const sensor_msgs::PointCloud2ConstPtr &msg)
void extractObject (const sensor_msgs::PointCloud2ConstPtr &msg)

Private Attributes

ros::Publisher arMarkerPub_
ar_pose::ARMarkers arPoseMarkers_
ros::Publisher bb_pcl
 publisher for the bounding box (for debugging)
double boundingbox_size
 size of the bounding box to crop
sensor_msgs::CvBridge bridge_
tf::TransformBroadcaster broadcaster_
sensor_msgs::CameraInfo cam_info_
ARParam cam_param_
 Camera Calibration Parameters.
image_transport::Subscriber cam_sub_
IplImage * capture_
PointCloud cloud_
ros::Subscriber cloud_sub_
int cloud_width_
ARMultiMarkerInfoT * config
 AR Marker Info.
char data_directory_ [FILENAME_MAX]
cv::Mat1f distances
 lookup table for distances between marker positions (for plausability checks)
bool getCamInfo_
bool gotcloud_
image_transport::ImageTransport it_
ros::Publisher kinect_pclPub_
double marker_dist_threshold
 threshold for marker position accuracy
ros::NodeHandle n_
ar_object::ObjectData_Tobject
int objectnum
char pattern_filename_ [FILENAME_MAX]
bool publishTf_
bool publishVisualMarkers_
ros::Publisher result_pcl
 publisher for the cropped point cloud
visualization_msgs::Marker rvizMarker_
ros::Publisher rvizMarkerPub_
message_filters::Subscriber
< sensor_msgs::PointCloud2 > 
sub
ros::Subscriber sub_
CvSize sz_
 camera image size
tf::TransformListener tf_
int threshold_
transform_type transformations
 Lookup table for getting the object coordinate system from 3 marker positions.

Detailed Description

Definition at line 82 of file ar_kinect.h.


Member Typedef Documentation

typedef boost::multi_array<CoordinateFrame*, 3> ARPublisher::transform_type [private]

Definition at line 158 of file ar_kinect.h.


Constructor & Destructor Documentation

Definition at line 128 of file ar_kinect.cpp.

Definition at line 185 of file ar_kinect.cpp.


Member Function Documentation

void ARPublisher::arInit ( ) [private]

Loads the patterns & initializes the lookup tables.

Definition at line 226 of file ar_kinect.cpp.

void ARPublisher::camInfoCallback ( const sensor_msgs::CameraInfoConstPtr &  cam_info) [private]

Camera parameters callback.

Definition at line 191 of file ar_kinect.cpp.

void ARPublisher::cloudCallback ( const sensor_msgs::PointCloud2ConstPtr &  msg) [private]

Callback for the point cloud from the Kinect. Estimates the marker's positions and calculates the object coordinate system.

Definition at line 269 of file ar_kinect.cpp.

void ARPublisher::extractObject ( const sensor_msgs::PointCloud2ConstPtr &  msg) [private]

Crops the sensor's point cloud at the bounding box around the object coordinate system and publishes it.

Definition at line 109 of file ar_kinect_extractobject.cpp.


Member Data Documentation

Definition at line 109 of file ar_kinect.h.

ar_pose::ARMarkers ARPublisher::arPoseMarkers_ [private]

Definition at line 133 of file ar_kinect.h.

publisher for the bounding box (for debugging)

Definition at line 156 of file ar_kinect.h.

size of the bounding box to crop

Definition at line 146 of file ar_kinect.h.

Definition at line 115 of file ar_kinect.h.

Definition at line 105 of file ar_kinect.h.

sensor_msgs::CameraInfo ARPublisher::cam_info_ [private]

Definition at line 116 of file ar_kinect.h.

ARParam ARPublisher::cam_param_ [private]

Camera Calibration Parameters.

Definition at line 125 of file ar_kinect.h.

Definition at line 107 of file ar_kinect.h.

IplImage* ARPublisher::capture_ [private]

Definition at line 140 of file ar_kinect.h.

Definition at line 117 of file ar_kinect.h.

Definition at line 108 of file ar_kinect.h.

Definition at line 142 of file ar_kinect.h.

ARMultiMarkerInfoT* ARPublisher::config [private]

AR Marker Info.

Definition at line 127 of file ar_kinect.h.

char ARPublisher::data_directory_[FILENAME_MAX] [private]

Definition at line 131 of file ar_kinect.h.

cv::Mat1f ARPublisher::distances [private]

lookup table for distances between marker positions (for plausability checks)

Definition at line 144 of file ar_kinect.h.

Definition at line 135 of file ar_kinect.h.

Definition at line 141 of file ar_kinect.h.

Definition at line 114 of file ar_kinect.h.

Definition at line 111 of file ar_kinect.h.

threshold for marker position accuracy

Definition at line 148 of file ar_kinect.h.

Definition at line 104 of file ar_kinect.h.

Definition at line 128 of file ar_kinect.h.

Definition at line 129 of file ar_kinect.h.

char ARPublisher::pattern_filename_[FILENAME_MAX] [private]

Definition at line 130 of file ar_kinect.h.

Definition at line 136 of file ar_kinect.h.

Definition at line 137 of file ar_kinect.h.

publisher for the cropped point cloud

Definition at line 154 of file ar_kinect.h.

visualization_msgs::Marker ARPublisher::rvizMarker_ [private]

Definition at line 121 of file ar_kinect.h.

Definition at line 120 of file ar_kinect.h.

message_filters::Subscriber<sensor_msgs::PointCloud2> ARPublisher::sub [private]

Definition at line 150 of file ar_kinect.h.

Definition at line 106 of file ar_kinect.h.

CvSize ARPublisher::sz_ [private]

camera image size

Definition at line 139 of file ar_kinect.h.

Definition at line 151 of file ar_kinect.h.

Definition at line 134 of file ar_kinect.h.

Lookup table for getting the object coordinate system from 3 marker positions.

Definition at line 160 of file ar_kinect.h.


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


ar_bounding_box
Author(s): Andreas Koch
autogenerated on Sun Jan 5 2014 11:40:40