Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
cob_3d_mapping::FOVSegmentation Class Reference

Class for segmenting a polygon array by the field of view of a camera. More...

#include <fov_segmentation.h>

List of all members.

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::Ptrpolygons_in_
 The input polygon array.

Detailed Description

Class for segmenting a polygon array by the field of view of a camera.

Definition at line 78 of file fov_segmentation.h.


Member Typedef Documentation

Definition at line 81 of file fov_segmentation.h.


Constructor & Destructor Documentation

Empty Constructor

Definition at line 72 of file fov_segmentation.cpp.

Empty Destructor

void

Definition at line 87 of file fov_segmentation.h.


Member Function Documentation

bool FOVSegmentation::ccw ( Eigen::Vector2f &  a,
Eigen::Vector2f &  b,
Eigen::Vector2f &  c 
) [protected]

Check if three points are sorted counterclockwise.

Parameters:
[in]aThe first point.
[in]bThe second point.
[in]cThe third point.
Returns:
True, if the points are counterclockwise.

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.

Parameters:
[in]polyThe polygon to be clipped.
[out]Theintersection 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.

Parameters:
[out]polygonsThe polygons inside the frustum.

Definition at line 81 of file fov_segmentation.cpp.

Set the FOV.

Parameters:
[in]fovField of view.

Definition at line 97 of file fov_segmentation.h.

void cob_3d_mapping::FOVSegmentation::setShapeArray ( std::vector< Polygon::Ptr > &  polygons) [inline]

Set the polygon array.

Parameters:
[in]polygonsThe polygon array.

Definition at line 106 of file fov_segmentation.h.


Member Data Documentation

The field of view.

Definition at line 143 of file fov_segmentation.h.

The input polygon array.

Definition at line 141 of file fov_segmentation.h.


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


cob_3d_fov_segmentation
Author(s): Georg Arbeiter
autogenerated on Wed Aug 26 2015 11:04:19