distances.h File Reference

#include <geometry_msgs/Point32.h>
#include <geometry_msgs/Point.h>
#include <Eigen/Core>
Include dependency graph for distances.h:
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::distances

Functions

void cloud_geometry::distances::createParallel2DLine (const std::vector< double > &line_a, std::vector< double > &line_b, double distance)
 Creates a parallel 2D line at a given distance in an X-Y plane (Z is ignored).
void cloud_geometry::distances::lineToLineSegment (const std::vector< double > &line_a, const std::vector< double > &line_b, std::vector< double > &segment)
 Get the shortest 3D segment between two 3D lines.
double cloud_geometry::distances::pointToLineDistance (const geometry_msgs::Point32 &p, const std::vector< double > &line_coefficients)
 Get the distance from a point to a line (represented by a point and a direction).
double cloud_geometry::distances::pointToLineDistance (const geometry_msgs::Point32 &p, const geometry_msgs::Point32 &q, const geometry_msgs::Point32 &dir)
 Get the distance from a point to a line (represented by a point and a direction).
double cloud_geometry::distances::pointToPlaneDistance (const geometry_msgs::Point32 &p, const Eigen::Vector4d &plane_coefficients)
 Get the distance from a point to a plane (unsigned) defined by ax+by+cz+d=0.
double cloud_geometry::distances::pointToPlaneDistance (const geometry_msgs::Point32 &p, double a, double b, double c, double d)
 Get the distance from a point to a plane (unsigned) defined by ax+by+cz+d=0.
double cloud_geometry::distances::pointToPlaneDistance (const geometry_msgs::Point32 &p, const std::vector< double > &plane_coefficients)
 Get the distance from a point to a plane (unsigned) defined by ax+by+cz+d=0.
double cloud_geometry::distances::pointToPlaneDistanceSigned (const geometry_msgs::Point32 &p, const Eigen::Vector4d &plane_coefficients)
 Get the distance from a point to a plane (signed) defined by ax+by+cz+d=0.
double cloud_geometry::distances::pointToPlaneDistanceSigned (const geometry_msgs::Point32 &p, double a, double b, double c, double d)
 Get the distance from a point to a plane (signed) defined by ax+by+cz+d=0.
double cloud_geometry::distances::pointToPlaneDistanceSigned (const geometry_msgs::Point32 &p, const std::vector< double > &plane_coefficients)
 Get the distance from a point to a plane (signed) defined by ax+by+cz+d=0.
double cloud_geometry::distances::pointToPointDistance (const geometry_msgs::Point &p1, const geometry_msgs::Point32 &p2)
 Get the distance from a 3D point to another 3D point.
double cloud_geometry::distances::pointToPointDistance (const geometry_msgs::Point32 &p1, const geometry_msgs::Point &p2)
 Get the distance from a 3D point to another 3D point.
double cloud_geometry::distances::pointToPointDistance (const geometry_msgs::Point &p1, const geometry_msgs::Point &p2)
 Get the distance from a 3D point to another 3D point.
double cloud_geometry::distances::pointToPointDistance (const geometry_msgs::Point32 &p1, const geometry_msgs::Point32 &p2)
 Get the distance from a 3D point to another 3D point.
double cloud_geometry::distances::pointToPointDistanceSqr (const geometry_msgs::Point &p1, const geometry_msgs::Point32 &p2)
 Get the squared distance from a 3D point to another 3D point.
double cloud_geometry::distances::pointToPointDistanceSqr (const geometry_msgs::Point32 &p1, const geometry_msgs::Point &p2)
 Get the squared distance from a 3D point to another 3D point.
double cloud_geometry::distances::pointToPointDistanceSqr (const geometry_msgs::Point &p1, const geometry_msgs::Point &p2)
 Get the squared distance from a 3D point to another 3D point.
double cloud_geometry::distances::pointToPointDistanceSqr (const geometry_msgs::Point32 &p1, const geometry_msgs::Point32 &p2)
 Get the squared distance from a 3D point to another 3D point.
double cloud_geometry::distances::pointToPointXYDistance (const geometry_msgs::Point32 &p1, const geometry_msgs::Point32 &p2)
 Get the distance from a 2D point to another 2D point in the XY plane.
double cloud_geometry::distances::pointToPointXYDistanceSqr (const geometry_msgs::Point32 &p1, const geometry_msgs::Point32 &p2)
 Get the squared distance from a 2D point to another 2D point in the XY plane.
double cloud_geometry::distances::pointToPointXZDistance (const geometry_msgs::Point32 &p1, const geometry_msgs::Point32 &p2)
 Get the distance from a 2D point to another 2D point in the XZ plane.
double cloud_geometry::distances::pointToPointXZDistanceSqr (const geometry_msgs::Point32 &p1, const geometry_msgs::Point32 &p2)
 Get the squared distance from a 2D point to another 2D point in the XZ plane.
double cloud_geometry::distances::pointToPointYZDistance (const geometry_msgs::Point32 &p1, const geometry_msgs::Point32 &p2)
 Get the distance from a 2D point to another 2D point in the YZ plane.
double cloud_geometry::distances::pointToPointYZDistanceSqr (const geometry_msgs::Point32 &p1, const geometry_msgs::Point32 &p2)
 Get the squared distance from a 2D point to another 2D point in the YZ plane.
double cloud_geometry::distances::pointToPolygonDistance (const geometry_msgs::Point32 &p, const geometry_msgs::Polygon &poly)
 Get the distance from a point to a 3D Polygon.
double cloud_geometry::distances::pointToPolygonDistanceSqr (const geometry_msgs::Point32 &p, const geometry_msgs::Polygon &poly)
 Get the squared distance from a point to a 3D Polygon.
double cloud_geometry::distances::pointToSphereDistance (const geometry_msgs::Point32 &p, double x, double y, double z, double r)
 Get the distance from a point to a sphere.
double cloud_geometry::distances::pointToSphereDistance (const geometry_msgs::Point32 &p, const std::vector< double > &sphere_coefficients)
 Get the distance from a point to a sphere.
 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:16 2013