Public Member Functions | Private Member Functions | Private Attributes
object_segmentation_gui::TableTransform Class Reference

#include <table_transform.h>

List of all members.

Public Member Functions

tabletop_object_detector::Table get3DTable (float alpha, float beta, float gamma, sensor_msgs::PointCloud &table_points, std_msgs::Header table_header)
void setParams (const sensor_msgs::CameraInfo &cam_info, float baseline, float up_direction)
 TableTransform ()
 ~TableTransform ()

Private Member Functions

pcl::ModelCoefficients convertTo3DPlane (const sensor_msgs::CameraInfo &camera_info, const float alpha, const float beta, const float gamma)
tf::Transform getPlaneTransform (pcl::ModelCoefficients coeffs, double up_direction)
template<class PointCloudType >
tabletop_object_detector::Table getTable (std_msgs::Header cloud_header, const tf::Transform &table_plane_trans, const PointCloudType &table_points)
bool transformPlanePoints (const tf::Transform &table_plane_trans, sensor_msgs::PointCloud &table_points)

Private Attributes

float baseline_
sensor_msgs::CameraInfo cam_info_
tf::TransformListener listener_
 A tf transform listener.
float up_direction_

Detailed Description

Definition at line 44 of file table_transform.h.


Constructor & Destructor Documentation

Definition at line 34 of file table_transform.cpp.

Definition at line 45 of file table_transform.cpp.


Member Function Documentation

pcl::ModelCoefficients object_segmentation_gui::TableTransform::convertTo3DPlane ( const sensor_msgs::CameraInfo &  camera_info,
const float  alpha,
const float  beta,
const float  gamma 
) [private]

Definition at line 86 of file table_transform.cpp.

tabletop_object_detector::Table object_segmentation_gui::TableTransform::get3DTable ( float  alpha,
float  beta,
float  gamma,
sensor_msgs::PointCloud table_points,
std_msgs::Header  table_header 
)

Definition at line 57 of file table_transform.cpp.

Assumes plane coefficients are of the form ax+by+cz+d=0, normalized

Definition at line 124 of file table_transform.cpp.

template<class PointCloudType >
tabletop_object_detector::Table object_segmentation_gui::TableTransform::getTable ( std_msgs::Header  cloud_header,
const tf::Transform table_plane_trans,
const PointCloudType &  table_points 
) [private]

Definition at line 191 of file table_transform.cpp.

void object_segmentation_gui::TableTransform::setParams ( const sensor_msgs::CameraInfo &  cam_info,
float  baseline,
float  up_direction 
)

Definition at line 48 of file table_transform.cpp.

Definition at line 159 of file table_transform.cpp.


Member Data Documentation

Definition at line 76 of file table_transform.h.

sensor_msgs::CameraInfo object_segmentation_gui::TableTransform::cam_info_ [private]

Definition at line 74 of file table_transform.h.

A tf transform listener.

Definition at line 80 of file table_transform.h.

Definition at line 77 of file table_transform.h.


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


object_segmentation_gui
Author(s): Jeannette Bohg
autogenerated on Fri Jan 3 2014 12:03:36