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 #ifndef JSK_RECOGNITION_UTILS_GEO_POLYGON_H_
00037 #define JSK_RECOGNITION_UTILS_GEO_POLYGON_H_
00038
00039 #include <Eigen/Geometry>
00040 #include <boost/shared_ptr.hpp>
00041 #include <pcl/point_cloud.h>
00042 #include <pcl/point_types.h>
00043 #include <boost/random.hpp>
00044 #include <geometry_msgs/Polygon.h>
00045 #include <jsk_recognition_msgs/PolygonArray.h>
00046
00047 #include "jsk_recognition_utils/geo/plane.h"
00048 #include "jsk_recognition_utils/geo/segment.h"
00049 #include "jsk_recognition_utils/sensor_model/camera_depth_sensor.h"
00050 #include "jsk_recognition_utils/pcl_conversion_util.h"
00051 #include "jsk_recognition_utils/random_util.h"
00052
00053 namespace jsk_recognition_utils
00054 {
00055 class Polygon: public Plane
00056 {
00057 public:
00058 typedef boost::shared_ptr<Polygon> Ptr;
00059 typedef boost::tuple<Ptr, Ptr> PtrPair;
00060 Polygon(const Vertices& vertices);
00061 Polygon(const Vertices& vertices,
00062 const std::vector<float>& coefficients);
00063 virtual ~Polygon();
00064 virtual std::vector<Polygon::Ptr> decomposeToTriangles();
00065 virtual void clearTriangleDecompositionCache() {
00066 cached_triangles_.clear();
00067 }
00068
00069 virtual Eigen::Vector3f getNormalFromVertices();
00070 virtual bool isTriangle();
00071 Eigen::Vector3f randomSampleLocalPoint(boost::mt19937& random_generator);
00072 virtual void getLocalMinMax(double& min_x, double& min_y,
00073 double& max_x, double& max_y);
00074 template <class PointT>
00075 typename pcl::PointCloud<PointT>::Ptr samplePoints(double grid_size)
00076 {
00077 typename pcl::PointCloud<PointT>::Ptr
00078 ret (new pcl::PointCloud<PointT>);
00079 double min_x, min_y, max_x, max_y;
00080 getLocalMinMax(min_x, min_y, max_x, max_y);
00081
00082
00083
00084
00085
00086 std::vector<Polygon::Ptr> triangles = decomposeToTriangles();
00087
00088 for (double x = min_x; x < max_x; x += grid_size) {
00089 for (double y = min_y; y < max_y; y += grid_size) {
00090 Eigen::Vector3f candidate(x, y, 0);
00091 Eigen::Vector3f candidate_global = coordinates() * candidate;
00092
00093 bool insidep = false;
00094 for (size_t i = 0; i < triangles.size(); i++) {
00095 if (triangles[i]->isInside(candidate_global)) {
00096 insidep = true;
00097 break;
00098 }
00099 }
00100 if (insidep) {
00101 PointT p;
00102 p.x = candidate_global[0];
00103 p.y = candidate_global[1];
00104 p.z = candidate_global[2];
00105 p.normal_x = normal_[0];
00106 p.normal_y = normal_[1];
00107 p.normal_z = normal_[2];
00108 ret->points.push_back(p);
00109 }
00110 }
00111 }
00112 return ret;
00113 }
00114
00119 std::vector<Segment::Ptr> edges() const;
00120
00140 virtual Eigen::Vector3f nearestPoint(const Eigen::Vector3f& p,
00141 double& distance);
00142 virtual size_t getNumVertices();
00143 virtual size_t getFarestPointIndex(const Eigen::Vector3f& O);
00144 virtual Eigen::Vector3f directionAtPoint(size_t i);
00145 virtual Eigen::Vector3f getVertex(size_t i);
00146 virtual PointIndexPair getNeighborIndex(size_t index);
00147 virtual Vertices getVertices() { return vertices_; };
00148 virtual double area();
00149 virtual bool isPossibleToRemoveTriangleAtIndex(
00150 size_t index,
00151 const Eigen::Vector3f& direction);
00152 virtual PtrPair separatePolygon(size_t index);
00158 virtual bool isInside(const Eigen::Vector3f& p);
00159 size_t previousIndex(size_t i);
00160 size_t nextIndex(size_t i);
00161
00162 static Polygon fromROSMsg(const geometry_msgs::Polygon& polygon);
00163 static Polygon::Ptr fromROSMsgPtr(const geometry_msgs::Polygon& polygon);
00164 static Polygon createPolygonWithSkip(const Vertices& vertices);
00165
00172 static std::vector<Polygon::Ptr> fromROSMsg(const jsk_recognition_msgs::PolygonArray& msg,
00173 const Eigen::Affine3f& offset);
00174
00180 virtual void transformBy(const Eigen::Affine3d& transform);
00181
00187 virtual void transformBy(const Eigen::Affine3f& transform);
00188
00195 virtual bool maskImage(const jsk_recognition_utils::CameraDepthSensor& model,
00196 cv::Mat& image) const;
00197
00202 virtual void drawLineToImage(const jsk_recognition_utils::CameraDepthSensor& model,
00203 cv::Mat& image,
00204 const cv::Scalar& color) const;
00205 virtual bool isConvex();
00206 virtual Eigen::Vector3f centroid();
00207 template<class PointT> void boundariesToPointCloud(
00208 pcl::PointCloud<PointT>& output) {
00209 output.points.resize(vertices_.size());
00210 for (size_t i = 0; i < vertices_.size(); i++) {
00211 Eigen::Vector3f v = vertices_[i];
00212 PointT p;
00213 p.x = v[0]; p.y = v[1]; p.z = v[2];
00214 output.points[i] = p;
00215 }
00216 output.height = 1;
00217 output.width = output.points.size();
00218 }
00219
00220 protected:
00221 Vertices vertices_;
00222 std::vector<Polygon::Ptr> cached_triangles_;
00223 private:
00224
00225 };
00226 }
00227
00228 #endif