#include <ObjectSegmentationGuiResult.h>
Public Types | |
enum | { NO_CLOUD_RECEIVED = 1 } |
enum | { NO_TABLE = 2 } |
enum | { OTHER_ERROR = 3 } |
enum | { SUCCESS = 4 } |
typedef std::vector < ::sensor_msgs::PointCloud_ < ContainerAllocator > , typename ContainerAllocator::template rebind < ::sensor_msgs::PointCloud_ < ContainerAllocator > >::other > | _clusters_type |
typedef int32_t | _result_type |
typedef ::tabletop_object_detector::Table_ < ContainerAllocator > | _table_type |
typedef boost::shared_ptr < ::object_segmentation_gui::ObjectSegmentationGuiResult_ < ContainerAllocator > const > | ConstPtr |
typedef boost::shared_ptr < ::object_segmentation_gui::ObjectSegmentationGuiResult_ < ContainerAllocator > > | Ptr |
typedef ObjectSegmentationGuiResult_ < ContainerAllocator > | Type |
Public Member Functions | |
ObjectSegmentationGuiResult_ () | |
ObjectSegmentationGuiResult_ (const ContainerAllocator &_alloc) | |
Public Attributes | |
boost::shared_ptr< std::map < std::string, std::string > > | __connection_header |
std::vector < ::sensor_msgs::PointCloud_ < ContainerAllocator > , typename ContainerAllocator::template rebind < ::sensor_msgs::PointCloud_ < ContainerAllocator > >::other > | clusters |
int32_t | result |
::tabletop_object_detector::Table_ < ContainerAllocator > | table |
Definition at line 23 of file ObjectSegmentationGuiResult.h.
typedef std::vector< ::sensor_msgs::PointCloud_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::sensor_msgs::PointCloud_<ContainerAllocator> >::other > object_segmentation_gui::ObjectSegmentationGuiResult_< ContainerAllocator >::_clusters_type |
Definition at line 43 of file ObjectSegmentationGuiResult.h.
typedef int32_t object_segmentation_gui::ObjectSegmentationGuiResult_< ContainerAllocator >::_result_type |
Definition at line 46 of file ObjectSegmentationGuiResult.h.
typedef ::tabletop_object_detector::Table_<ContainerAllocator> object_segmentation_gui::ObjectSegmentationGuiResult_< ContainerAllocator >::_table_type |
Definition at line 40 of file ObjectSegmentationGuiResult.h.
typedef boost::shared_ptr< ::object_segmentation_gui::ObjectSegmentationGuiResult_<ContainerAllocator> const> object_segmentation_gui::ObjectSegmentationGuiResult_< ContainerAllocator >::ConstPtr |
Definition at line 55 of file ObjectSegmentationGuiResult.h.
typedef boost::shared_ptr< ::object_segmentation_gui::ObjectSegmentationGuiResult_<ContainerAllocator> > object_segmentation_gui::ObjectSegmentationGuiResult_< ContainerAllocator >::Ptr |
Definition at line 54 of file ObjectSegmentationGuiResult.h.
typedef ObjectSegmentationGuiResult_<ContainerAllocator> object_segmentation_gui::ObjectSegmentationGuiResult_< ContainerAllocator >::Type |
Definition at line 24 of file ObjectSegmentationGuiResult.h.
anonymous enum |
Definition at line 49 of file ObjectSegmentationGuiResult.h.
anonymous enum |
Definition at line 50 of file ObjectSegmentationGuiResult.h.
anonymous enum |
Definition at line 51 of file ObjectSegmentationGuiResult.h.
anonymous enum |
Definition at line 52 of file ObjectSegmentationGuiResult.h.
object_segmentation_gui::ObjectSegmentationGuiResult_< ContainerAllocator >::ObjectSegmentationGuiResult_ | ( | ) | [inline] |
Definition at line 26 of file ObjectSegmentationGuiResult.h.
object_segmentation_gui::ObjectSegmentationGuiResult_< ContainerAllocator >::ObjectSegmentationGuiResult_ | ( | const ContainerAllocator & | _alloc | ) | [inline] |
Definition at line 33 of file ObjectSegmentationGuiResult.h.
boost::shared_ptr<std::map<std::string, std::string> > object_segmentation_gui::ObjectSegmentationGuiResult_< ContainerAllocator >::__connection_header |
Definition at line 56 of file ObjectSegmentationGuiResult.h.
std::vector< ::sensor_msgs::PointCloud_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::sensor_msgs::PointCloud_<ContainerAllocator> >::other > object_segmentation_gui::ObjectSegmentationGuiResult_< ContainerAllocator >::clusters |
Definition at line 44 of file ObjectSegmentationGuiResult.h.
int32_t object_segmentation_gui::ObjectSegmentationGuiResult_< ContainerAllocator >::result |
Definition at line 47 of file ObjectSegmentationGuiResult.h.
::tabletop_object_detector::Table_<ContainerAllocator> object_segmentation_gui::ObjectSegmentationGuiResult_< ContainerAllocator >::table |
Definition at line 41 of file ObjectSegmentationGuiResult.h.