#include <OccupancyGrid.h>
Public Types | |
typedef ::geometry_msgs::Point32_ < ContainerAllocator > | _center_type |
typedef std::vector< uint32_t, typename ContainerAllocator::template rebind< uint32_t >::other > | _data_type |
typedef ::geometry_msgs::Point32_ < ContainerAllocator > | _grid_size_type |
typedef ::std_msgs::Header_ < ContainerAllocator > | _header_type |
typedef int32_t | _occupancy_threshold_type |
typedef ::geometry_msgs::Point32_ < ContainerAllocator > | _resolution_type |
typedef boost::shared_ptr < ::point_cloud_ros::OccupancyGrid_ < ContainerAllocator > const > | ConstPtr |
typedef boost::shared_ptr < ::point_cloud_ros::OccupancyGrid_ < ContainerAllocator > > | Ptr |
typedef OccupancyGrid_ < ContainerAllocator > | Type |
Public Member Functions | |
OccupancyGrid_ () | |
OccupancyGrid_ (const ContainerAllocator &_alloc) | |
Public Attributes | |
boost::shared_ptr< std::map < std::string, std::string > > | __connection_header |
::geometry_msgs::Point32_ < ContainerAllocator > | center |
std::vector< uint32_t, typename ContainerAllocator::template rebind< uint32_t >::other > | data |
::geometry_msgs::Point32_ < ContainerAllocator > | grid_size |
::std_msgs::Header_ < ContainerAllocator > | header |
int32_t | occupancy_threshold |
::geometry_msgs::Point32_ < ContainerAllocator > | resolution |
Definition at line 25 of file OccupancyGrid.h.
typedef ::geometry_msgs::Point32_<ContainerAllocator> point_cloud_ros::OccupancyGrid_< ContainerAllocator >::_center_type |
Definition at line 54 of file OccupancyGrid.h.
typedef std::vector<uint32_t, typename ContainerAllocator::template rebind<uint32_t>::other > point_cloud_ros::OccupancyGrid_< ContainerAllocator >::_data_type |
Definition at line 51 of file OccupancyGrid.h.
typedef ::geometry_msgs::Point32_<ContainerAllocator> point_cloud_ros::OccupancyGrid_< ContainerAllocator >::_grid_size_type |
Definition at line 57 of file OccupancyGrid.h.
typedef ::std_msgs::Header_<ContainerAllocator> point_cloud_ros::OccupancyGrid_< ContainerAllocator >::_header_type |
Definition at line 48 of file OccupancyGrid.h.
typedef int32_t point_cloud_ros::OccupancyGrid_< ContainerAllocator >::_occupancy_threshold_type |
Definition at line 63 of file OccupancyGrid.h.
typedef ::geometry_msgs::Point32_<ContainerAllocator> point_cloud_ros::OccupancyGrid_< ContainerAllocator >::_resolution_type |
Definition at line 60 of file OccupancyGrid.h.
typedef boost::shared_ptr< ::point_cloud_ros::OccupancyGrid_<ContainerAllocator> const> point_cloud_ros::OccupancyGrid_< ContainerAllocator >::ConstPtr |
Definition at line 68 of file OccupancyGrid.h.
typedef boost::shared_ptr< ::point_cloud_ros::OccupancyGrid_<ContainerAllocator> > point_cloud_ros::OccupancyGrid_< ContainerAllocator >::Ptr |
Definition at line 67 of file OccupancyGrid.h.
typedef OccupancyGrid_<ContainerAllocator> point_cloud_ros::OccupancyGrid_< ContainerAllocator >::Type |
Definition at line 26 of file OccupancyGrid.h.
point_cloud_ros::OccupancyGrid_< ContainerAllocator >::OccupancyGrid_ | ( | ) | [inline] |
Definition at line 28 of file OccupancyGrid.h.
point_cloud_ros::OccupancyGrid_< ContainerAllocator >::OccupancyGrid_ | ( | const ContainerAllocator & | _alloc | ) | [inline] |
Definition at line 38 of file OccupancyGrid.h.
boost::shared_ptr<std::map<std::string, std::string> > point_cloud_ros::OccupancyGrid_< ContainerAllocator >::__connection_header |
Definition at line 69 of file OccupancyGrid.h.
::geometry_msgs::Point32_<ContainerAllocator> point_cloud_ros::OccupancyGrid_< ContainerAllocator >::center |
Definition at line 55 of file OccupancyGrid.h.
std::vector<uint32_t, typename ContainerAllocator::template rebind<uint32_t>::other > point_cloud_ros::OccupancyGrid_< ContainerAllocator >::data |
Definition at line 52 of file OccupancyGrid.h.
::geometry_msgs::Point32_<ContainerAllocator> point_cloud_ros::OccupancyGrid_< ContainerAllocator >::grid_size |
Definition at line 58 of file OccupancyGrid.h.
::std_msgs::Header_<ContainerAllocator> point_cloud_ros::OccupancyGrid_< ContainerAllocator >::header |
Definition at line 49 of file OccupancyGrid.h.
int32_t point_cloud_ros::OccupancyGrid_< ContainerAllocator >::occupancy_threshold |
Definition at line 64 of file OccupancyGrid.h.
::geometry_msgs::Point32_<ContainerAllocator> point_cloud_ros::OccupancyGrid_< ContainerAllocator >::resolution |
Definition at line 61 of file OccupancyGrid.h.