Class for segmenting a polygon array by the field of view of a camera. More...
#include <fov_segmentation.h>
Public Types | |
typedef std::vector < Polygon::Ptr >::iterator | polygon_iterator |
Public Member Functions | |
void | compute (std::vector< Polygon::Ptr > &polygons) |
Compute an return the polygons inside the FOV frustum. | |
FOVSegmentation () | |
void | setFOV (FieldOfView &fov) |
Set the FOV. | |
void | setShapeArray (std::vector< Polygon::Ptr > &polygons) |
Set the polygon array. | |
~FOVSegmentation () | |
Protected Member Functions | |
bool | ccw (Eigen::Vector2f &a, Eigen::Vector2f &b, Eigen::Vector2f &c) |
Check if three points are sorted counterclockwise. | |
void | clipFOVandPlane (Polygon::Ptr &poly, std::vector< Eigen::Vector3f > &intersections) |
Clip the FOV with a planar polygon. | |
Protected Attributes | |
FieldOfView | fov_ |
The field of view. | |
std::vector< Polygon::Ptr > | polygons_in_ |
The input polygon array. |
Class for segmenting a polygon array by the field of view of a camera.
Definition at line 78 of file fov_segmentation.h.
typedef std::vector<Polygon::Ptr>::iterator cob_3d_mapping::FOVSegmentation::polygon_iterator |
Definition at line 81 of file fov_segmentation.h.
Empty Constructor
Definition at line 72 of file fov_segmentation.cpp.
cob_3d_mapping::FOVSegmentation::~FOVSegmentation | ( | ) | [inline] |
bool FOVSegmentation::ccw | ( | Eigen::Vector2f & | a, |
Eigen::Vector2f & | b, | ||
Eigen::Vector2f & | c | ||
) | [protected] |
Check if three points are sorted counterclockwise.
[in] | a | The first point. |
[in] | b | The second point. |
[in] | c | The third point. |
Definition at line 76 of file fov_segmentation.cpp.
void FOVSegmentation::clipFOVandPlane | ( | Polygon::Ptr & | poly, |
std::vector< Eigen::Vector3f > & | intersections | ||
) | [protected] |
Clip the FOV with a planar polygon.
[in] | poly | The polygon to be clipped. |
[out] | The | intersection points between FOV and polygon. |
Definition at line 148 of file fov_segmentation.cpp.
void FOVSegmentation::compute | ( | std::vector< Polygon::Ptr > & | polygons | ) |
Compute an return the polygons inside the FOV frustum.
[out] | polygons | The polygons inside the frustum. |
Definition at line 81 of file fov_segmentation.cpp.
void cob_3d_mapping::FOVSegmentation::setFOV | ( | FieldOfView & | fov | ) | [inline] |
void cob_3d_mapping::FOVSegmentation::setShapeArray | ( | std::vector< Polygon::Ptr > & | polygons | ) | [inline] |
Set the polygon array.
[in] | polygons | The polygon array. |
Definition at line 106 of file fov_segmentation.h.
FieldOfView cob_3d_mapping::FOVSegmentation::fov_ [protected] |
The field of view.
Definition at line 143 of file fov_segmentation.h.
std::vector<Polygon::Ptr> cob_3d_mapping::FOVSegmentation::polygons_in_ [protected] |
The input polygon array.
Definition at line 141 of file fov_segmentation.h.