#include <grid_map.h>
| Public Types | |
| typedef Columns::iterator | ColumnIterator | 
| typedef std::map< int, RowIndices > | Columns | 
| typedef boost::shared_ptr< GridMap > | Ptr | 
| typedef std::set< int > | RowIndices | 
| typedef std::set< int >::iterator | RowIterator | 
| Public Member Functions | |
| virtual void | add (GridMap &other) | 
| virtual bool | check4Neighbor (int x, int y) | 
| virtual void | decrease (int i) | 
| virtual void | fillRegion (const Eigen::Vector3f &start, std::vector< GridIndex::Ptr > &output) | 
| virtual void | fillRegion (const GridIndex::Ptr start, std::vector< GridIndex::Ptr > &output) | 
| virtual std::vector< float > | getCoefficients () | 
| virtual unsigned int | getGeneration () | 
| virtual bool | getValue (const GridIndex &index) | 
| virtual bool | getValue (const GridIndex::Ptr &index) | 
| virtual bool | getValue (const int x, const int y) | 
| virtual unsigned int | getVoteNum () | 
| GridMap (double resolution, const std::vector< float > &coefficients) | |
| virtual void | gridToPoint (const GridIndex &index, Eigen::Vector3f &pos) | 
| virtual void | gridToPoint (GridIndex::Ptr index, Eigen::Vector3f &pos) | 
| virtual void | gridToPoint2 (const GridIndex &index, Eigen::Vector3f &pos) | 
| virtual int | heightOffset () | 
| virtual void | indicesToPointCloud (const std::vector< GridIndex::Ptr > &indices, pcl::PointCloud< pcl::PointXYZRGB >::Ptr cloud) | 
| virtual bool | isBinsOccupied (const Eigen::Vector3f &p) | 
| virtual boost::tuple< int, int > | minMaxX () | 
| virtual boost::tuple< int, int > | minMaxY () | 
| virtual int | normalizedHeight () | 
| virtual int | normalizedIndex (int width_offset, int height_offset, int step, int elem_size, int original_x, int original_y) | 
| virtual int | normalizedWidth () | 
| virtual void | originPose (Eigen::Affine3d &output) | 
| virtual void | originPose (Eigen::Affine3f &output) | 
| virtual void | pointToIndex (const Eigen::Vector3f &point, GridIndex::Ptr index) | 
| virtual void | pointToIndex (const pcl::PointXYZRGB &point, GridIndex::Ptr index) | 
| virtual GridIndex::Ptr | registerIndex (const GridIndex::Ptr &index) | 
| virtual GridIndex::Ptr | registerIndex (const int x, const int y) | 
| virtual std::vector< GridIndex::Ptr > | registerLine (const pcl::PointXYZRGB &from, const pcl::PointXYZRGB &to) | 
| virtual void | registerPoint (const pcl::PointXYZRGB &point) | 
| virtual void | registerPointCloud (pcl::PointCloud< pcl::PointXYZRGB >::Ptr cloud) | 
| virtual void | removeIndex (const GridIndex::Ptr &index) | 
| virtual void | setGeneration (unsigned int generation) | 
| virtual ConvexPolygon::Ptr | toConvexPolygon () | 
| virtual cv::Mat | toImage () | 
| virtual void | toMsg (jsk_recognition_msgs::SparseOccupancyGrid &grid) | 
| virtual Plane | toPlane () | 
| virtual Plane::Ptr | toPlanePtr () | 
| virtual pcl::PointCloud< pcl::PointXYZ >::Ptr | toPointCloud () | 
| virtual void | vote () | 
| virtual int | widthOffset () | 
| virtual | ~GridMap () | 
| Protected Member Functions | |
| virtual void | decreaseOne () | 
| Protected Attributes | |
| double | d_ | 
| Columns | data_ | 
| Eigen::Vector3f | ex_ | 
| Eigen::Vector3f | ey_ | 
| unsigned int | generation_ | 
| std::vector< GridLine::Ptr > | lines_ | 
| Eigen::Vector3f | normal_ | 
| Eigen::Vector3f | O_ | 
| double | resolution_ | 
| unsigned int | vote_ | 
Definition at line 87 of file grid_map.h.
| typedef Columns::iterator jsk_recognition_utils::GridMap::ColumnIterator | 
Definition at line 125 of file grid_map.h.
| typedef std::map<int, RowIndices> jsk_recognition_utils::GridMap::Columns | 
Definition at line 124 of file grid_map.h.
Definition at line 122 of file grid_map.h.
| typedef std::set<int> jsk_recognition_utils::GridMap::RowIndices | 
Definition at line 123 of file grid_map.h.
| typedef std::set<int>::iterator jsk_recognition_utils::GridMap::RowIterator | 
Definition at line 126 of file grid_map.h.
| jsk_recognition_utils::GridMap::GridMap | ( | double | resolution, | 
| const std::vector< float > & | coefficients | ||
| ) | 
Definition at line 49 of file grid_map.cpp.
| 
 | virtual | 
Definition at line 70 of file grid_map.cpp.
| 
 | virtual | 
Definition at line 608 of file grid_map.cpp.
| 
 | virtual | 
Definition at line 568 of file grid_map.cpp.
| 
 | virtual | 
Definition at line 601 of file grid_map.cpp.
| 
 | protectedvirtual | 
Definition at line 580 of file grid_map.cpp.
| 
 | virtual | 
Definition at line 337 of file grid_map.cpp.
| 
 | virtual | 
Definition at line 293 of file grid_map.cpp.
| 
 | virtual | 
Definition at line 417 of file grid_map.cpp.
| 
 | virtual | 
Definition at line 441 of file grid_map.cpp.
| 
 | virtual | 
Definition at line 283 of file grid_map.cpp.
| 
 | virtual | 
Definition at line 288 of file grid_map.cpp.
| 
 | virtual | 
Definition at line 247 of file grid_map.cpp.
| 
 | virtual | 
Definition at line 432 of file grid_map.cpp.
| 
 | virtual | 
Definition at line 234 of file grid_map.cpp.
| 
 | virtual | 
Definition at line 229 of file grid_map.cpp.
| 
 | virtual | 
Definition at line 240 of file grid_map.cpp.
| 
 | virtual | 
Definition at line 526 of file grid_map.cpp.
| 
 | virtual | 
Definition at line 344 of file grid_map.cpp.
| 
 | virtual | 
Definition at line 458 of file grid_map.cpp.
| 
 | virtual | 
Definition at line 466 of file grid_map.cpp.
| 
 | virtual | 
Definition at line 484 of file grid_map.cpp.
| 
 | virtual | 
Definition at line 513 of file grid_map.cpp.
| 
 | virtual | 
Definition at line 533 of file grid_map.cpp.
| 
 | virtual | 
Definition at line 507 of file grid_map.cpp.
| 
 | virtual | 
Definition at line 372 of file grid_map.cpp.
| 
 | virtual | 
Definition at line 359 of file grid_map.cpp.
| 
 | virtual | 
Definition at line 223 of file grid_map.cpp.
| 
 | virtual | 
Definition at line 218 of file grid_map.cpp.
| 
 | virtual | 
Definition at line 90 of file grid_map.cpp.
| 
 | virtual | 
Definition at line 75 of file grid_map.cpp.
| 
 | virtual | 
Definition at line 103 of file grid_map.cpp.
| 
 | virtual | 
Definition at line 95 of file grid_map.cpp.
| 
 | virtual | 
Definition at line 210 of file grid_map.cpp.
| 
 | virtual | 
Definition at line 446 of file grid_map.cpp.
| 
 | virtual | 
Definition at line 437 of file grid_map.cpp.
| 
 | virtual | 
Definition at line 652 of file grid_map.cpp.
| 
 | virtual | 
Definition at line 544 of file grid_map.cpp.
| 
 | virtual | 
Definition at line 379 of file grid_map.cpp.
| 
 | virtual | 
Definition at line 405 of file grid_map.cpp.
| 
 | virtual | 
Definition at line 410 of file grid_map.cpp.
| 
 | virtual | 
Definition at line 629 of file grid_map.cpp.
| 
 | virtual | 
Definition at line 427 of file grid_map.cpp.
| 
 | virtual | 
Definition at line 519 of file grid_map.cpp.
| 
 | protected | 
Definition at line 183 of file grid_map.h.
| 
 | protected | 
Definition at line 188 of file grid_map.h.
| 
 | protected | 
Definition at line 185 of file grid_map.h.
| 
 | protected | 
Definition at line 185 of file grid_map.h.
| 
 | protected | 
Definition at line 190 of file grid_map.h.
| 
 | protected | 
Definition at line 187 of file grid_map.h.
| 
 | protected | 
Definition at line 182 of file grid_map.h.
| 
 | protected | 
Definition at line 179 of file grid_map.h.
| 
 | protected | 
Definition at line 178 of file grid_map.h.
| 
 | protected | 
Definition at line 189 of file grid_map.h.