#include <Shape.h>
Public Types | |
| enum | { SPHERE = 0 } | 
| enum | { BOX = 1 } | 
| enum | { CYLINDER = 2 } | 
| enum | { MESH = 3 } | 
| typedef std::vector< double,  typename ContainerAllocator::template rebind< double >::other >  | _dimensions_type | 
| typedef std::vector< int32_t,  typename ContainerAllocator::template rebind< int32_t >::other >  | _triangles_type | 
| typedef int8_t | _type_type | 
| typedef std::vector < ::geometry_msgs::Point_ < ContainerAllocator > , typename ContainerAllocator::template rebind < ::geometry_msgs::Point_ < ContainerAllocator > >::other >  | _vertices_type | 
| typedef boost::shared_ptr < ::arm_navigation_msgs::Shape_ < ContainerAllocator > const >  | ConstPtr | 
| typedef boost::shared_ptr < ::arm_navigation_msgs::Shape_ < ContainerAllocator > >  | Ptr | 
| typedef Shape_ < ContainerAllocator >  | Type | 
Public Member Functions | |
| Shape_ () | |
| Shape_ (const ContainerAllocator &_alloc) | |
Public Attributes | |
| boost::shared_ptr< std::map < std::string, std::string > >  | __connection_header | 
| std::vector< double, typename  ContainerAllocator::template rebind< double >::other >  | dimensions | 
| std::vector< int32_t, typename  ContainerAllocator::template rebind< int32_t >::other >  | triangles | 
| int8_t | type | 
| std::vector < ::geometry_msgs::Point_ < ContainerAllocator > , typename ContainerAllocator::template rebind < ::geometry_msgs::Point_ < ContainerAllocator > >::other >  | vertices | 
| typedef std::vector<double, typename ContainerAllocator::template rebind<double>::other > arm_navigation_msgs::Shape_< ContainerAllocator >::_dimensions_type | 
| typedef std::vector<int32_t, typename ContainerAllocator::template rebind<int32_t>::other > arm_navigation_msgs::Shape_< ContainerAllocator >::_triangles_type | 
| typedef int8_t arm_navigation_msgs::Shape_< ContainerAllocator >::_type_type | 
| typedef std::vector< ::geometry_msgs::Point_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::Point_<ContainerAllocator> >::other > arm_navigation_msgs::Shape_< ContainerAllocator >::_vertices_type | 
| typedef boost::shared_ptr< ::arm_navigation_msgs::Shape_<ContainerAllocator> const> arm_navigation_msgs::Shape_< ContainerAllocator >::ConstPtr | 
| typedef boost::shared_ptr< ::arm_navigation_msgs::Shape_<ContainerAllocator> > arm_navigation_msgs::Shape_< ContainerAllocator >::Ptr | 
| typedef Shape_<ContainerAllocator> arm_navigation_msgs::Shape_< ContainerAllocator >::Type | 
| anonymous enum | 
| anonymous enum | 
| anonymous enum | 
| anonymous enum | 
| arm_navigation_msgs::Shape_< ContainerAllocator >::Shape_ | ( | ) |  [inline] | 
        
| arm_navigation_msgs::Shape_< ContainerAllocator >::Shape_ | ( | const ContainerAllocator & | _alloc | ) |  [inline] | 
        
| boost::shared_ptr<std::map<std::string, std::string> > arm_navigation_msgs::Shape_< ContainerAllocator >::__connection_header | 
| std::vector<double, typename ContainerAllocator::template rebind<double>::other > arm_navigation_msgs::Shape_< ContainerAllocator >::dimensions | 
| std::vector<int32_t, typename ContainerAllocator::template rebind<int32_t>::other > arm_navigation_msgs::Shape_< ContainerAllocator >::triangles | 
| int8_t arm_navigation_msgs::Shape_< ContainerAllocator >::type | 
| std::vector< ::geometry_msgs::Point_<ContainerAllocator> , typename ContainerAllocator::template rebind< ::geometry_msgs::Point_<ContainerAllocator> >::other > arm_navigation_msgs::Shape_< ContainerAllocator >::vertices |