|
bool | allEdgesLongerThan (double thr) |
|
| ConvexPolygon (const Vertices &vertices) |
|
| ConvexPolygon (const Vertices &vertices, const std::vector< float > &coefficients) |
|
double | distanceFromVertices (const Eigen::Vector3f &p) |
|
bool | distanceSmallerThan (const Eigen::Vector3f &p, double distance_threshold) |
|
bool | distanceSmallerThan (const Eigen::Vector3f &p, double distance_threshold, double &output_distance) |
|
virtual ConvexPolygon | flipConvex () |
|
virtual Eigen::Vector3f | getCentroid () |
|
virtual bool | isProjectableInside (const Eigen::Vector3f &p) |
|
virtual Ptr | magnify (const double scale_factor) |
|
virtual Ptr | magnifyByDistance (const double distance) |
|
virtual void | project (const Eigen::Vector3f &p, Eigen::Vector3f &output) |
|
virtual void | project (const Eigen::Vector3d &p, Eigen::Vector3d &output) |
|
virtual void | project (const Eigen::Vector3d &p, Eigen::Vector3f &output) |
|
virtual void | project (const Eigen::Vector3f &p, Eigen::Vector3d &output) |
|
virtual void | projectOnPlane (const Eigen::Vector3f &p, Eigen::Vector3f &output) |
|
virtual void | projectOnPlane (const Eigen::Affine3f &p, Eigen::Affine3f &output) |
|
geometry_msgs::Polygon | toROSMsg () |
|
virtual double | area () |
|
template<class PointT > |
void | boundariesToPointCloud (pcl::PointCloud< PointT > &output) |
|
virtual Eigen::Vector3f | centroid () |
|
virtual void | clearTriangleDecompositionCache () |
|
virtual std::vector< Polygon::Ptr > | decomposeToTriangles () |
|
virtual Eigen::Vector3f | directionAtPoint (size_t i) |
|
double | distance (const Eigen::Vector3f &point) |
| Compute distance between point and this polygon. More...
|
|
double | distance (const Eigen::Vector3f &point, Eigen::Vector3f &nearest_point) |
| Compute distance between point and this polygon. Nearest point on this polygon can be gotten. More...
|
|
virtual void | drawLineToImage (const jsk_recognition_utils::CameraDepthSensor &model, cv::Mat &image, const cv::Scalar &color, const int line_width=1) const |
| draw line of polygons on image. More...
|
|
std::vector< Segment::Ptr > | edges () const |
| get all the edges as point of Segment. More...
|
|
virtual size_t | getFarestPointIndex (const Eigen::Vector3f &O) |
|
virtual void | getLocalMinMax (double &min_x, double &min_y, double &max_x, double &max_y) |
|
virtual PointIndexPair | getNeighborIndex (size_t index) |
|
virtual Eigen::Vector3f | getNormalFromVertices () |
|
virtual size_t | getNumVertices () |
|
virtual Eigen::Vector3f | getVertex (size_t i) |
|
virtual Vertices | getVertices () |
|
virtual bool | isConvex () |
|
virtual bool | isInside (const Eigen::Vector3f &p) |
| return true if p is inside of polygon. p should be in global coordinates. More...
|
|
virtual bool | isPossibleToRemoveTriangleAtIndex (size_t index, const Eigen::Vector3f &direction) |
|
virtual bool | isTriangle () |
|
virtual bool | maskImage (const jsk_recognition_utils::CameraDepthSensor &model, cv::Mat &image) const |
| generate mask image of the polygon. if all the points are outside of field-of-view, returns false. More...
|
|
virtual Eigen::Vector3f | nearestPoint (const Eigen::Vector3f &p, double &distance) |
| Compute nearest point from p on this polygon. More...
|
|
size_t | nextIndex (size_t i) |
|
| Polygon (const Vertices &vertices) |
|
| Polygon (const Vertices &vertices, const std::vector< float > &coefficients) |
|
size_t | previousIndex (size_t i) |
|
Eigen::Vector3f | randomSampleLocalPoint (boost::mt19937 &random_generator) |
|
template<class PointT > |
pcl::PointCloud< PointT >::Ptr | samplePoints (double grid_size) |
|
virtual PtrPair | separatePolygon (size_t index) |
|
virtual void | transformBy (const Eigen::Affine3d &transform) |
| transform Polygon with given transform. cached triangles is cleared. More...
|
|
virtual void | transformBy (const Eigen::Affine3f &transform) |
| transform Polygon with given transform. cached triangles is cleared. More...
|
|
virtual | ~Polygon () |
|
virtual double | angle (const Plane &another) |
|
virtual double | angle (const Eigen::Vector3f &vector) |
|
virtual Eigen::Affine3f | coordinates () |
|
virtual double | distance (const Plane &another) |
|
virtual double | distanceToPoint (const Eigen::Vector4f p) |
|
virtual double | distanceToPoint (const Eigen::Vector3f p) |
|
virtual Plane::Ptr | faceToOrigin () |
|
virtual Plane | flip () |
|
virtual double | getD () |
|
virtual Eigen::Vector3f | getNormal () |
|
virtual Eigen::Vector3f | getPointOnPlane () |
|
virtual bool | isSameDirection (const Plane &another) |
|
virtual bool | isSameDirection (const Eigen::Vector3f &another_normal) |
|
| Plane (const std::vector< float > &coefficients) |
|
| Plane (const boost::array< float, 4 > &coefficients) |
|
| Plane (Eigen::Vector3f normal, double d) |
|
| Plane (Eigen::Vector3f normal, Eigen::Vector3f p) |
|
virtual void | project (const Eigen::Affine3d &pose, Eigen::Affine3d &output) |
|
virtual void | project (const Eigen::Affine3f &pose, Eigen::Affine3f &output) |
|
virtual double | signedDistanceToPoint (const Eigen::Vector4f p) |
|
virtual double | signedDistanceToPoint (const Eigen::Vector3f p) |
|
virtual void | toCoefficients (std::vector< float > &output) |
|
virtual std::vector< float > | toCoefficients () |
|
virtual Plane | transform (const Eigen::Affine3d &transform) |
|
virtual Plane | transform (const Eigen::Affine3f &transform) |
|
virtual | ~Plane () |
|
Definition at line 48 of file convex_polygon.h.