Public Types | Public Member Functions | Static Public Member Functions | Protected Attributes
jsk_recognition_utils::Polygon Class Reference

#include <polygon.h>

Inheritance diagram for jsk_recognition_utils::Polygon:
Inheritance graph
[legend]

List of all members.

Public Types

typedef boost::shared_ptr
< Polygon
Ptr
typedef boost::tuple< Ptr, PtrPtrPair

Public Member Functions

virtual double area ()
template<class PointT >
void boundariesToPointCloud (pcl::PointCloud< PointT > &output)
virtual Eigen::Vector3f centroid ()
virtual void clearTriangleDecompositionCache ()
virtual std::vector< Polygon::PtrdecomposeToTriangles ()
virtual Eigen::Vector3f directionAtPoint (size_t i)
double distance (const Eigen::Vector3f &point)
 Compute distance between point and this polygon.
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.
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.
std::vector< Segment::Ptredges () const
 get all the edges as point of Segment.
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.
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.
virtual Eigen::Vector3f nearestPoint (const Eigen::Vector3f &p, double &distance)
 Compute nearest point from p on this polygon.
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.
virtual void transformBy (const Eigen::Affine3f &transform)
 transform Polygon with given transform. cached triangles is cleared.
virtual ~Polygon ()

Static Public Member Functions

static Polygon createPolygonWithSkip (const Vertices &vertices)
static Polygon fromROSMsg (const geometry_msgs::Polygon &polygon)
static std::vector< Polygon::PtrfromROSMsg (const jsk_recognition_msgs::PolygonArray &msg, const Eigen::Affine3f &offset=Eigen::Affine3f::Identity())
 convert jsk_recognition_msgs::PolygonArray to std::vector<Polygon::Ptr>. It requires offset transformation in the 2nd argument.
static Polygon::Ptr fromROSMsgPtr (const geometry_msgs::Polygon &polygon)

Protected Attributes

std::vector< Polygon::Ptrcached_triangles_
Vertices vertices_

Detailed Description

Definition at line 55 of file polygon.h.


Member Typedef Documentation

typedef boost::shared_ptr<Polygon> jsk_recognition_utils::Polygon::Ptr

Reimplemented from jsk_recognition_utils::Plane.

Reimplemented in jsk_recognition_utils::ConvexPolygon.

Definition at line 58 of file polygon.h.

Definition at line 59 of file polygon.h.


Constructor & Destructor Documentation

Definition at line 87 of file polygon.cpp.

jsk_recognition_utils::Polygon::Polygon ( const Vertices vertices,
const std::vector< float > &  coefficients 
)

Definition at line 94 of file polygon.cpp.

Definition at line 101 of file polygon.cpp.


Member Function Documentation

Definition at line 127 of file polygon.cpp.

template<class PointT >
void jsk_recognition_utils::Polygon::boundariesToPointCloud ( pcl::PointCloud< PointT > &  output) [inline]

Definition at line 222 of file polygon.h.

Eigen::Vector3f jsk_recognition_utils::Polygon::centroid ( ) [virtual]

Definition at line 62 of file polygon.cpp.

Definition at line 65 of file polygon.h.

Definition at line 46 of file polygon.cpp.

Definition at line 482 of file polygon.cpp.

Eigen::Vector3f jsk_recognition_utils::Polygon::directionAtPoint ( size_t  i) [virtual]

Definition at line 142 of file polygon.cpp.

double jsk_recognition_utils::Polygon::distance ( const Eigen::Vector3f &  point)

Compute distance between point and this polygon.

Definition at line 225 of file polygon.cpp.

double jsk_recognition_utils::Polygon::distance ( const Eigen::Vector3f &  point,
Eigen::Vector3f &  nearest_point 
)

Compute distance between point and this polygon. Nearest point on this polygon can be gotten.

Definition at line 231 of file polygon.cpp.

void jsk_recognition_utils::Polygon::drawLineToImage ( const jsk_recognition_utils::CameraDepthSensor model,
cv::Mat &  image,
const cv::Scalar &  color,
const int  line_width = 1 
) const [virtual]

draw line of polygons on image.

Definition at line 442 of file polygon.cpp.

get all the edges as point of Segment.

Definition at line 212 of file polygon.cpp.

Polygon jsk_recognition_utils::Polygon::fromROSMsg ( const geometry_msgs::Polygon &  polygon) [static]

Reimplemented in jsk_recognition_utils::ConvexPolygon.

Definition at line 564 of file polygon.cpp.

std::vector< Polygon::Ptr > jsk_recognition_utils::Polygon::fromROSMsg ( const jsk_recognition_msgs::PolygonArray &  msg,
const Eigen::Affine3f &  offset = Eigen::Affine3f::Identity() 
) [static]

convert jsk_recognition_msgs::PolygonArray to std::vector<Polygon::Ptr>. It requires offset transformation in the 2nd argument.

Definition at line 588 of file polygon.cpp.

Polygon::Ptr jsk_recognition_utils::Polygon::fromROSMsgPtr ( const geometry_msgs::Polygon &  polygon) [static]

Reimplemented in jsk_recognition_utils::ConvexPolygon.

Definition at line 576 of file polygon.cpp.

size_t jsk_recognition_utils::Polygon::getFarestPointIndex ( const Eigen::Vector3f &  O) [virtual]

Definition at line 106 of file polygon.cpp.

void jsk_recognition_utils::Polygon::getLocalMinMax ( double &  min_x,
double &  min_y,
double &  max_x,
double &  max_y 
) [virtual]

Definition at line 166 of file polygon.cpp.

Definition at line 121 of file polygon.cpp.

Definition at line 533 of file polygon.cpp.

Definition at line 267 of file polygon.cpp.

Eigen::Vector3f jsk_recognition_utils::Polygon::getVertex ( size_t  i) [virtual]

Definition at line 271 of file polygon.cpp.

Definition at line 161 of file polygon.h.

Definition at line 464 of file polygon.cpp.

bool jsk_recognition_utils::Polygon::isInside ( const Eigen::Vector3f &  p) [virtual]

return true if p is inside of polygon. p should be in global coordinates.

Definition at line 600 of file polygon.cpp.

bool jsk_recognition_utils::Polygon::isPossibleToRemoveTriangleAtIndex ( size_t  index,
const Eigen::Vector3f &  direction 
) [virtual]

Definition at line 305 of file polygon.cpp.

Definition at line 162 of file polygon.cpp.

bool jsk_recognition_utils::Polygon::maskImage ( const jsk_recognition_utils::CameraDepthSensor model,
cv::Mat &  image 
) const [virtual]

generate mask image of the polygon. if all the points are outside of field-of-view, returns false.

Definition at line 412 of file polygon.cpp.

Eigen::Vector3f jsk_recognition_utils::Polygon::nearestPoint ( const Eigen::Vector3f &  p,
double &  distance 
) [virtual]

Compute nearest point from p on this polygon.

This method first project p onth the polygon and if the projected point is inside of polygon, the projected point is the nearest point. If not, distances between the point and edges are computed and search the nearest point.

In case of searching edges, it is achieved in brute-force searching and if the number of edges is huge, it may take a lot of time to compute.

This method cannot be used for const instance because triangle decomposition will change the cache in the instance.

Distance between p and nearest point is stored in distance.

Definition at line 239 of file polygon.cpp.

Definition at line 554 of file polygon.cpp.

Definition at line 544 of file polygon.cpp.

Eigen::Vector3f jsk_recognition_utils::Polygon::randomSampleLocalPoint ( boost::mt19937 &  random_generator)

Definition at line 185 of file polygon.cpp.

template<class PointT >
pcl::PointCloud<PointT>::Ptr jsk_recognition_utils::Polygon::samplePoints ( double  grid_size) [inline]

Definition at line 75 of file polygon.h.

Definition at line 275 of file polygon.cpp.

void jsk_recognition_utils::Polygon::transformBy ( const Eigen::Affine3d &  transform) [virtual]

transform Polygon with given transform. cached triangles is cleared.

Definition at line 389 of file polygon.cpp.

void jsk_recognition_utils::Polygon::transformBy ( const Eigen::Affine3f &  transform) [virtual]

transform Polygon with given transform. cached triangles is cleared.

Definition at line 396 of file polygon.cpp.


Member Data Documentation

Definition at line 237 of file polygon.h.

Definition at line 236 of file polygon.h.


The documentation for this class was generated from the following files:


jsk_recognition_utils
Author(s):
autogenerated on Sun Oct 8 2017 02:42:48