All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines
Public Types | Public Member Functions | Public Attributes
fast_plane_detection::Plane_< ContainerAllocator > Struct Template Reference

#include <Plane.h>

List of all members.

Public Types

enum  { SUCCESS = 1 }
enum  { FEW_INLIERS = 2 }
enum  { NO_PLANE = 3 }
enum  { OTHER_ERROR = 4 }
typedef
::geometry_msgs::Point32_
< ContainerAllocator > 
_bottom_left_type
typedef
::geometry_msgs::Point32_
< ContainerAllocator > 
_bottom_right_type
typedef float _error_type
typedef
::geometry_msgs::Vector3Stamped_
< ContainerAllocator > 
_normal_type
typedef int32_t _percentage_disp_inliers_type
typedef float _percentage_inliers_type
typedef int32_t _percentage_valid_disp_type
typedef
::geometry_msgs::PointStamped_
< ContainerAllocator > 
_plane_point_type
typedef
::geometry_msgs::PoseStamped_
< ContainerAllocator > 
_pose_type
typedef int32_t _result_type
typedef
::geometry_msgs::PointStamped_
< ContainerAllocator > 
_slave_point_type
typedef
::geometry_msgs::Point32_
< ContainerAllocator > 
_top_left_type
typedef
::geometry_msgs::Point32_
< ContainerAllocator > 
_top_right_type
typedef boost::shared_ptr
< ::fast_plane_detection::Plane_
< ContainerAllocator > const > 
ConstPtr
typedef boost::shared_ptr
< ::fast_plane_detection::Plane_
< ContainerAllocator > > 
Ptr
typedef Plane_
< ContainerAllocator > 
Type

Public Member Functions

 Plane_ ()
 Plane_ (const ContainerAllocator &_alloc)

Public Attributes

boost::shared_ptr< std::map
< std::string, std::string > > 
__connection_header
::geometry_msgs::Point32_
< ContainerAllocator > 
bottom_left
::geometry_msgs::Point32_
< ContainerAllocator > 
bottom_right
float error
::geometry_msgs::Vector3Stamped_
< ContainerAllocator > 
normal
int32_t percentage_disp_inliers
float percentage_inliers
int32_t percentage_valid_disp
::geometry_msgs::PointStamped_
< ContainerAllocator > 
plane_point
::geometry_msgs::PoseStamped_
< ContainerAllocator > 
pose
int32_t result
::geometry_msgs::PointStamped_
< ContainerAllocator > 
slave_point
::geometry_msgs::Point32_
< ContainerAllocator > 
top_left
::geometry_msgs::Point32_
< ContainerAllocator > 
top_right

Detailed Description

template<class ContainerAllocator>
struct fast_plane_detection::Plane_< ContainerAllocator >

Definition at line 29 of file Plane.h.


Member Typedef Documentation

template<class ContainerAllocator>
typedef ::geometry_msgs::Point32_<ContainerAllocator> fast_plane_detection::Plane_< ContainerAllocator >::_bottom_left_type

Definition at line 84 of file Plane.h.

template<class ContainerAllocator>
typedef ::geometry_msgs::Point32_<ContainerAllocator> fast_plane_detection::Plane_< ContainerAllocator >::_bottom_right_type

Definition at line 87 of file Plane.h.

template<class ContainerAllocator>
typedef float fast_plane_detection::Plane_< ContainerAllocator >::_error_type

Definition at line 102 of file Plane.h.

template<class ContainerAllocator>
typedef ::geometry_msgs::Vector3Stamped_<ContainerAllocator> fast_plane_detection::Plane_< ContainerAllocator >::_normal_type

Definition at line 72 of file Plane.h.

template<class ContainerAllocator>
typedef int32_t fast_plane_detection::Plane_< ContainerAllocator >::_percentage_disp_inliers_type

Definition at line 96 of file Plane.h.

template<class ContainerAllocator>
typedef float fast_plane_detection::Plane_< ContainerAllocator >::_percentage_inliers_type

Definition at line 93 of file Plane.h.

template<class ContainerAllocator>
typedef int32_t fast_plane_detection::Plane_< ContainerAllocator >::_percentage_valid_disp_type

Definition at line 99 of file Plane.h.

template<class ContainerAllocator>
typedef ::geometry_msgs::PointStamped_<ContainerAllocator> fast_plane_detection::Plane_< ContainerAllocator >::_plane_point_type

Definition at line 69 of file Plane.h.

template<class ContainerAllocator>
typedef ::geometry_msgs::PoseStamped_<ContainerAllocator> fast_plane_detection::Plane_< ContainerAllocator >::_pose_type

Definition at line 66 of file Plane.h.

template<class ContainerAllocator>
typedef int32_t fast_plane_detection::Plane_< ContainerAllocator >::_result_type

Definition at line 90 of file Plane.h.

template<class ContainerAllocator>
typedef ::geometry_msgs::PointStamped_<ContainerAllocator> fast_plane_detection::Plane_< ContainerAllocator >::_slave_point_type

Definition at line 75 of file Plane.h.

template<class ContainerAllocator>
typedef ::geometry_msgs::Point32_<ContainerAllocator> fast_plane_detection::Plane_< ContainerAllocator >::_top_left_type

Definition at line 78 of file Plane.h.

template<class ContainerAllocator>
typedef ::geometry_msgs::Point32_<ContainerAllocator> fast_plane_detection::Plane_< ContainerAllocator >::_top_right_type

Definition at line 81 of file Plane.h.

template<class ContainerAllocator>
typedef boost::shared_ptr< ::fast_plane_detection::Plane_<ContainerAllocator> const> fast_plane_detection::Plane_< ContainerAllocator >::ConstPtr

Definition at line 111 of file Plane.h.

template<class ContainerAllocator>
typedef boost::shared_ptr< ::fast_plane_detection::Plane_<ContainerAllocator> > fast_plane_detection::Plane_< ContainerAllocator >::Ptr

Definition at line 110 of file Plane.h.

template<class ContainerAllocator>
typedef Plane_<ContainerAllocator> fast_plane_detection::Plane_< ContainerAllocator >::Type

Definition at line 30 of file Plane.h.


Member Enumeration Documentation

template<class ContainerAllocator>
anonymous enum
Enumerator:
SUCCESS 

Definition at line 105 of file Plane.h.

template<class ContainerAllocator>
anonymous enum
Enumerator:
FEW_INLIERS 

Definition at line 106 of file Plane.h.

template<class ContainerAllocator>
anonymous enum
Enumerator:
NO_PLANE 

Definition at line 107 of file Plane.h.

template<class ContainerAllocator>
anonymous enum
Enumerator:
OTHER_ERROR 

Definition at line 108 of file Plane.h.


Constructor & Destructor Documentation

template<class ContainerAllocator>
fast_plane_detection::Plane_< ContainerAllocator >::Plane_ ( ) [inline]

Definition at line 32 of file Plane.h.

template<class ContainerAllocator>
fast_plane_detection::Plane_< ContainerAllocator >::Plane_ ( const ContainerAllocator &  _alloc) [inline]

Definition at line 49 of file Plane.h.


Member Data Documentation

template<class ContainerAllocator>
boost::shared_ptr<std::map<std::string, std::string> > fast_plane_detection::Plane_< ContainerAllocator >::__connection_header

Definition at line 112 of file Plane.h.

template<class ContainerAllocator>
::geometry_msgs::Point32_<ContainerAllocator> fast_plane_detection::Plane_< ContainerAllocator >::bottom_left

Definition at line 85 of file Plane.h.

template<class ContainerAllocator>
::geometry_msgs::Point32_<ContainerAllocator> fast_plane_detection::Plane_< ContainerAllocator >::bottom_right

Definition at line 88 of file Plane.h.

template<class ContainerAllocator>
float fast_plane_detection::Plane_< ContainerAllocator >::error

Definition at line 103 of file Plane.h.

template<class ContainerAllocator>
::geometry_msgs::Vector3Stamped_<ContainerAllocator> fast_plane_detection::Plane_< ContainerAllocator >::normal

Definition at line 73 of file Plane.h.

template<class ContainerAllocator>
int32_t fast_plane_detection::Plane_< ContainerAllocator >::percentage_disp_inliers

Definition at line 97 of file Plane.h.

template<class ContainerAllocator>
float fast_plane_detection::Plane_< ContainerAllocator >::percentage_inliers

Definition at line 94 of file Plane.h.

template<class ContainerAllocator>
int32_t fast_plane_detection::Plane_< ContainerAllocator >::percentage_valid_disp

Definition at line 100 of file Plane.h.

template<class ContainerAllocator>
::geometry_msgs::PointStamped_<ContainerAllocator> fast_plane_detection::Plane_< ContainerAllocator >::plane_point

Definition at line 70 of file Plane.h.

template<class ContainerAllocator>
::geometry_msgs::PoseStamped_<ContainerAllocator> fast_plane_detection::Plane_< ContainerAllocator >::pose

Definition at line 67 of file Plane.h.

template<class ContainerAllocator>
int32_t fast_plane_detection::Plane_< ContainerAllocator >::result

Definition at line 91 of file Plane.h.

template<class ContainerAllocator>
::geometry_msgs::PointStamped_<ContainerAllocator> fast_plane_detection::Plane_< ContainerAllocator >::slave_point

Definition at line 76 of file Plane.h.

template<class ContainerAllocator>
::geometry_msgs::Point32_<ContainerAllocator> fast_plane_detection::Plane_< ContainerAllocator >::top_left

Definition at line 79 of file Plane.h.

template<class ContainerAllocator>
::geometry_msgs::Point32_<ContainerAllocator> fast_plane_detection::Plane_< ContainerAllocator >::top_right

Definition at line 82 of file Plane.h.


The documentation for this struct was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines


fast_plane_detection
Author(s): Jeannette Bohg
autogenerated on Wed Jan 23 2013 16:52:54