35 #ifndef JSK_RECOGNITION_UTILS_GRID_MAP_H_ 36 #define JSK_RECOGNITION_UTILS_GRID_MAP_H_ 37 #include <jsk_recognition_msgs/SparseOccupancyGrid.h> 41 #include <pcl/point_types.h> 42 #include <pcl/point_cloud.h> 45 #include <Eigen/Geometry> 46 #include <boost/tuple/tuple.hpp> 49 #include <opencv2/opencv.hpp> 60 typedef std::map<int, RowIndices>
Columns;
63 GridMap(
double resolution,
const std::vector<float>& coefficients);
66 virtual std::vector<GridIndex::Ptr>
registerLine(
const pcl::PointXYZRGB& from,
const pcl::PointXYZRGB& to);
74 pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud);
77 virtual bool getValue(
const int x,
const int y);
81 virtual void fillRegion(
const Eigen::Vector3f& start, std::vector<GridIndex::Ptr>& output);
84 virtual void originPose(Eigen::Affine3f& output);
85 virtual void originPose(Eigen::Affine3d& output);
86 virtual void toMsg(jsk_recognition_msgs::SparseOccupancyGrid& grid);
97 virtual boost::tuple<int, int>
minMaxX();
98 virtual boost::tuple<int, int>
minMaxY();
104 int original_x,
int original_y);
108 virtual pcl::PointCloud<pcl::PointXYZ>::Ptr
toPointCloud();
virtual boost::tuple< int, int > minMaxX()
virtual void add(GridMap &other)
GridMap(double resolution, const std::vector< float > &coefficients)
virtual void registerPoint(const pcl::PointXYZRGB &point)
virtual void decrease(int i)
virtual void indicesToPointCloud(const std::vector< GridIndex::Ptr > &indices, pcl::PointCloud< pcl::PointXYZRGB >::Ptr cloud)
virtual std::vector< GridIndex::Ptr > registerLine(const pcl::PointXYZRGB &from, const pcl::PointXYZRGB &to)
Columns::iterator ColumnIterator
virtual void removeIndex(const GridIndex::Ptr &index)
virtual bool getValue(const GridIndex::Ptr &index)
virtual int normalizedHeight()
virtual cv::Mat toImage()
std::set< int >::iterator RowIterator
virtual void pointToIndex(const pcl::PointXYZRGB &point, GridIndex::Ptr index)
virtual pcl::PointCloud< pcl::PointXYZ >::Ptr toPointCloud()
virtual void registerPointCloud(pcl::PointCloud< pcl::PointXYZRGB >::Ptr cloud)
virtual bool check4Neighbor(int x, int y)
virtual bool isBinsOccupied(const Eigen::Vector3f &p)
virtual int heightOffset()
virtual std::vector< float > getCoefficients()
virtual int widthOffset()
virtual void gridToPoint(GridIndex::Ptr index, Eigen::Vector3f &pos)
boost::shared_ptr< GridMap > Ptr
virtual Plane::Ptr toPlanePtr()
std::map< int, RowIndices > Columns
virtual void fillRegion(const Eigen::Vector3f &start, std::vector< GridIndex::Ptr > &output)
virtual void setGeneration(unsigned int generation)
virtual ConvexPolygon::Ptr toConvexPolygon()
virtual unsigned int getGeneration()
virtual unsigned int getVoteNum()
virtual void decreaseOne()
std::set< int > RowIndices
virtual void originPose(Eigen::Affine3f &output)
virtual void gridToPoint2(const GridIndex &index, Eigen::Vector3f &pos)
virtual int normalizedIndex(int width_offset, int height_offset, int step, int elem_size, int original_x, int original_y)
virtual void toMsg(jsk_recognition_msgs::SparseOccupancyGrid &grid)
virtual int normalizedWidth()
std::vector< GridLine::Ptr > lines_
virtual GridIndex::Ptr registerIndex(const GridIndex::Ptr &index)
virtual boost::tuple< int, int > minMaxY()