Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef JSK_FOOTSTEP_PLANNER_ANN_GRID_H_
00038 #define JSK_FOOTSTEP_PLANNER_ANN_GRID_H_
00039
00040 #include <boost/tuple/tuple.hpp>
00041 #include <boost/unordered/unordered_set.hpp>
00042 #include <pcl/point_types.h>
00043 #include <pcl/point_cloud.h>
00044 #include <pcl/PointIndices.h>
00045
00046 #include <opencv2/opencv.hpp>
00047
00048 #include <ros/ros.h>
00049
00050 namespace jsk_footstep_planner
00051 {
00052 class ANNGridCell
00053 {
00054 public:
00055 typedef boost::shared_ptr<ANNGridCell> Ptr;
00056 typedef boost::unordered_set<size_t> Indices;
00057 ANNGridCell() {}
00058 virtual ~ANNGridCell() {}
00059 virtual void add(size_t i)
00060 {
00061 indices_.insert(i);
00062 }
00063 virtual Indices get()
00064 {
00065 return indices_;
00066 }
00067
00068 virtual void fill(Indices& out)
00069 {
00070 for (Indices::iterator it = indices_.begin(); it != indices_.end(); ++it) {
00071 out.insert(*it);
00072 }
00073 }
00074 virtual void fill(std::vector<int>& out)
00075 {
00076 for (Indices::iterator it = indices_.begin(); it != indices_.end(); ++it) {
00077 out.push_back(*it);
00078 }
00079 }
00080 protected:
00081 Indices indices_;
00082 private:
00083
00084 };
00085
00086
00093 class ANNGrid
00094 {
00095 public:
00096 typedef boost::shared_ptr<ANNGrid> Ptr;
00097 typedef cv::Point Index;
00098 typedef std::vector<Index> IndexArray;
00099 ANNGrid(const double grid_size): grid_size_(grid_size) {}
00100 virtual ~ANNGrid()
00101 {
00102 }
00103
00104 virtual void build(const pcl::PointCloud<pcl::PointNormal>& cloud);
00105
00106 virtual Index pointToIndex(const pcl::PointNormal& p) const
00107 {
00108 Eigen::Vector3f v = p.getVector3fMap();
00109 Eigen::Vector3f translated_point = v - min_point_;
00110 int i = (int)std::floor(translated_point[0] / grid_size_);
00111 int j = (int)std::floor(translated_point[1] / grid_size_);
00112 return cv::Point(i, j);
00113 }
00114
00115 virtual Index pointToIndex(const Eigen::Vector3f& p) const
00116 {
00117 Eigen::Vector3f translated_point = p - min_point_;
00118 int i = (int)std::floor(translated_point[0] / grid_size_);
00119 int j = (int)std::floor(translated_point[1] / grid_size_);
00120 return cv::Point(i, j);
00121 }
00122
00123 inline ANNGridCell::Ptr getCell(size_t i, size_t j)
00124 {
00125
00126 if (cells_.size() > i) {
00127 if (cells_[i].size() > j) {
00128 return cells_[i][j];
00129 }
00130 else {
00131 return ANNGridCell::Ptr();
00132 }
00133 }
00134 else {
00135 return ANNGridCell::Ptr();
00136 }
00137 }
00138
00139 virtual void approximateSearch(const Eigen::Vector3f& v, pcl::PointIndices& indices);
00140 virtual IndexArray bresenham(const Eigen::Vector3f& p0, const Eigen::Vector3f& p1);
00141
00142 virtual IndexArray fill(const IndexArray& filled);
00143 virtual IndexArray fillByBox(
00144 const Eigen::Vector3f& p0, const Eigen::Vector3f& p1,
00145 const Eigen::Vector3f& p2, const Eigen::Vector3f& p3);
00146 virtual void approximateSearchInBox(
00147 const Eigen::Vector3f& p0, const Eigen::Vector3f& p1,
00148 const Eigen::Vector3f& p2, const Eigen::Vector3f& p3,
00149 pcl::PointIndices& indices);
00150
00151 virtual IndexArray box(const Eigen::Vector3f& p0, const Eigen::Vector3f& p1,
00152 const Eigen::Vector3f& p2, const Eigen::Vector3f& p3);
00153 virtual void toImage(cv::Mat& mat);
00154 virtual void toImage(cv::Mat& mat, const IndexArray& pixels);
00155 protected:
00156
00157 const double grid_size_;
00158 std::vector<std::vector<ANNGridCell::Ptr> > cells_;
00159 cv::Mat mat_;
00160 Eigen::Vector3f min_point_;
00161 private:
00162
00163 };
00164 }
00165
00166 #endif