areas.cpp File Reference

#include <stereo_wall_detection/geometry/point.h>
#include <stereo_wall_detection/geometry/areas.h>
#include <stereo_wall_detection/geometry/distances.h>
#include <stereo_wall_detection/geometry/transforms.h>
#include <stereo_wall_detection/geometry/intersections.h>
#include <Eigen/Core>
#include <Eigen/Geometry>
#include "Core"
#include "src/Core/util/DisableMSVCWarnings.h"
#include "SVD"
#include "LU"
#include <limits>
#include "src/Geometry/OrthoMethods.h"
#include "src/Geometry/EulerAngles.h"
#include "src/Core/util/EnableMSVCWarnings.h"
#include <cfloat>
#include <algorithm>
Include dependency graph for areas.cpp:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

namespace  cloud_geometry
namespace  cloud_geometry::areas

Functions

double cloud_geometry::areas::compute2DPolygonalArea (const geometry_msgs::Polygon &polygon)
 Compute the area of a 2D planar polygon patch. The normal is computed automatically.
double cloud_geometry::areas::compute2DPolygonalArea (const geometry_msgs::Polygon &polygon, const std::vector< double > &normal)
 Compute the area of a 2D planar polygon patch - using a given normal.
double cloud_geometry::areas::compute2DPolygonalArea (const sensor_msgs::PointCloud &points, const std::vector< double > &normal)
 Compute the area of a 2D planar polygon patch - using a given normal.
bool cloud_geometry::areas::compute2DPolygonNormal (const geometry_msgs::Polygon &poly, std::vector< double > &normal)
void cloud_geometry::areas::convexHull2D (const std::vector< geometry_msgs::Point32 > &points, geometry_msgs::Polygon &hull)
 Compute a 2D convex hull using Andrew's monotone chain algorithm.
void cloud_geometry::areas::convexHull2D (const sensor_msgs::PointCloud &points, const std::vector< int > &indices, const std::vector< double > &coeff, geometry_msgs::Polygon &hull)
 Compute a 2D convex hull in 3D space using Andrew's monotone chain algorithm.
bool cloud_geometry::areas::isPointIn2DPolygon (const geometry_msgs::Point32 &point, const geometry_msgs::Polygon &polygon)
 Check if a 2d point (X and Y coordinates considered only!) is inside or outisde a given polygon.
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


stereo_wall_detection
Author(s): Radu Bogdan Rusu
autogenerated on Fri Jan 11 09:37:15 2013