Functions | |
void | 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 | 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 | 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 | 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 | 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 | 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 | 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 | 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 | 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 | 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 | pointToPointDistance (const geometry_msgs::Point32 &p1, const geometry_msgs::Point32 &p2) |
Get the distance from a 3D point to another 3D point. | |
double | pointToPointDistance (const geometry_msgs::Point &p1, const geometry_msgs::Point &p2) |
Get the distance from a 3D point to another 3D point. | |
double | pointToPointDistance (const geometry_msgs::Point32 &p1, const geometry_msgs::Point &p2) |
Get the distance from a 3D point to another 3D point. | |
double | pointToPointDistance (const geometry_msgs::Point &p1, const geometry_msgs::Point32 &p2) |
Get the distance from a 3D point to another 3D point. | |
double | pointToPointDistanceSqr (const geometry_msgs::Point32 &p1, const geometry_msgs::Point32 &p2) |
Get the squared distance from a 3D point to another 3D point. | |
double | pointToPointDistanceSqr (const geometry_msgs::Point &p1, const geometry_msgs::Point &p2) |
Get the squared distance from a 3D point to another 3D point. | |
double | pointToPointDistanceSqr (const geometry_msgs::Point32 &p1, const geometry_msgs::Point &p2) |
Get the squared distance from a 3D point to another 3D point. | |
double | pointToPointDistanceSqr (const geometry_msgs::Point &p1, const geometry_msgs::Point32 &p2) |
Get the squared distance from a 3D point to another 3D point. | |
double | 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 | 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 | 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 | 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 | 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 | 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 | pointToPolygonDistance (const geometry_msgs::Point32 &p, const geometry_msgs::Polygon &poly) |
Get the distance from a point to a 3D Polygon. | |
double | pointToPolygonDistanceSqr (const geometry_msgs::Point32 &p, const geometry_msgs::Polygon &poly) |
Get the squared distance from a point to a 3D Polygon. | |
double | pointToSphereDistance (const geometry_msgs::Point32 &p, const std::vector< double > &sphere_coefficients) |
Get the distance from a point to a sphere. | |
double | pointToSphereDistance (const geometry_msgs::Point32 &p, double x, double y, double z, double r) |
Get the distance from a point to a sphere. |
void cloud_geometry::distances::createParallel2DLine | ( | const std::vector< double > & | line_a, |
std::vector< double > & | line_b, | ||
double | distance | ||
) | [inline] |
Creates a parallel 2D line at a given distance in an X-Y plane (Z is ignored)
line_a | the 3D coefficients of the input line (point, direction) |
line_b | the 3D coefficients of the resultant parallel line (point, direction), with point.z copied and direction.z = 0 |
distance | the desired distance between the lines |
Definition at line 310 of file distances.h.
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.
line_a | the coefficients of the first line (point, direction) |
line_b | the coefficients of the second line (point, direction) |
segment | the resulting two 3D points that mark the beginning and the end of the segment |
Definition at line 99 of file distances.cpp.
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)
p | a point |
q | the point on the line |
dir | the direction of the line |
Definition at line 48 of file distances.cpp.
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)
p | a point |
line_coefficients | the line coefficients (point.x point.y point.z direction.x direction.y direction.z) |
Definition at line 71 of file distances.cpp.
double cloud_geometry::distances::pointToPlaneDistance | ( | const geometry_msgs::Point32 & | p, |
const std::vector< double > & | plane_coefficients | ||
) | [inline] |
Get the distance from a point to a plane (unsigned) defined by ax+by+cz+d=0.
p | a point |
plane_coefficients | the normalized coefficients (a, b, c, d) of a plane |
Definition at line 243 of file distances.h.
double cloud_geometry::distances::pointToPlaneDistance | ( | const geometry_msgs::Point32 & | p, |
double | a, | ||
double | b, | ||
double | c, | ||
double | d | ||
) | [inline] |
Get the distance from a point to a plane (unsigned) defined by ax+by+cz+d=0.
p | a point |
a | the normalized a coefficient of a plane |
b | the normalized b coefficient of a plane |
c | the normalized c coefficient of a plane |
d | the normalized d coefficient of a plane |
Definition at line 256 of file distances.h.
double cloud_geometry::distances::pointToPlaneDistance | ( | const geometry_msgs::Point32 & | p, |
const Eigen::Vector4d & | plane_coefficients | ||
) | [inline] |
Get the distance from a point to a plane (unsigned) defined by ax+by+cz+d=0.
p | a point |
plane_coefficients | the normalized coefficients (a, b, c, d) of a plane |
Definition at line 266 of file distances.h.
double cloud_geometry::distances::pointToPlaneDistanceSigned | ( | const geometry_msgs::Point32 & | p, |
const std::vector< double > & | plane_coefficients | ||
) | [inline] |
Get the distance from a point to a plane (signed) defined by ax+by+cz+d=0.
p | a point |
plane_coefficients | the normalized coefficients (a, b, c, d) of a plane |
Definition at line 209 of file distances.h.
double cloud_geometry::distances::pointToPlaneDistanceSigned | ( | const geometry_msgs::Point32 & | p, |
double | a, | ||
double | b, | ||
double | c, | ||
double | d | ||
) | [inline] |
Get the distance from a point to a plane (signed) defined by ax+by+cz+d=0.
p | a point |
a | the normalized a coefficient of a plane |
b | the normalized b coefficient of a plane |
c | the normalized c coefficient of a plane |
d | the normalized d coefficient of a plane |
Definition at line 222 of file distances.h.
double cloud_geometry::distances::pointToPlaneDistanceSigned | ( | const geometry_msgs::Point32 & | p, |
const Eigen::Vector4d & | plane_coefficients | ||
) | [inline] |
Get the distance from a point to a plane (signed) defined by ax+by+cz+d=0.
p | a point |
plane_coefficients | the normalized coefficients (a, b, c, d) of a plane |
Definition at line 232 of file distances.h.
double cloud_geometry::distances::pointToPointDistance | ( | const geometry_msgs::Point32 & | p1, |
const geometry_msgs::Point32 & | p2 | ||
) | [inline] |
Get the distance from a 3D point to another 3D point.
p1 | the first point |
p2 | the second point |
Definition at line 129 of file distances.h.
double cloud_geometry::distances::pointToPointDistance | ( | const geometry_msgs::Point & | p1, |
const geometry_msgs::Point & | p2 | ||
) | [inline] |
Get the distance from a 3D point to another 3D point.
p1 | the first point |
p2 | the second point |
Definition at line 151 of file distances.h.
double cloud_geometry::distances::pointToPointDistance | ( | const geometry_msgs::Point32 & | p1, |
const geometry_msgs::Point & | p2 | ||
) | [inline] |
Get the distance from a 3D point to another 3D point.
p1 | the first point |
p2 | the second point |
Definition at line 173 of file distances.h.
double cloud_geometry::distances::pointToPointDistance | ( | const geometry_msgs::Point & | p1, |
const geometry_msgs::Point32 & | p2 | ||
) | [inline] |
Get the distance from a 3D point to another 3D point.
p1 | the first point |
p2 | the second point |
Definition at line 195 of file distances.h.
double cloud_geometry::distances::pointToPointDistanceSqr | ( | const geometry_msgs::Point32 & | p1, |
const geometry_msgs::Point32 & | p2 | ||
) | [inline] |
Get the squared distance from a 3D point to another 3D point.
p1 | the first point |
p2 | the second point |
Definition at line 118 of file distances.h.
double cloud_geometry::distances::pointToPointDistanceSqr | ( | const geometry_msgs::Point & | p1, |
const geometry_msgs::Point & | p2 | ||
) | [inline] |
Get the squared distance from a 3D point to another 3D point.
p1 | the first point |
p2 | the second point |
Definition at line 140 of file distances.h.
double cloud_geometry::distances::pointToPointDistanceSqr | ( | const geometry_msgs::Point32 & | p1, |
const geometry_msgs::Point & | p2 | ||
) | [inline] |
Get the squared distance from a 3D point to another 3D point.
p1 | the first point |
p2 | the second point |
Definition at line 162 of file distances.h.
double cloud_geometry::distances::pointToPointDistanceSqr | ( | const geometry_msgs::Point & | p1, |
const geometry_msgs::Point32 & | p2 | ||
) | [inline] |
Get the squared distance from a 3D point to another 3D point.
p1 | the first point |
p2 | the second point |
Definition at line 184 of file distances.h.
double cloud_geometry::distances::pointToPointXYDistance | ( | const geometry_msgs::Point32 & | p1, |
const geometry_msgs::Point32 & | p2 | ||
) | [inline] |
Get the distance from a 2D point to another 2D point in the XY plane.
p1 | the first point |
p2 | the second point |
Definition at line 63 of file distances.h.
double cloud_geometry::distances::pointToPointXYDistanceSqr | ( | const geometry_msgs::Point32 & | p1, |
const geometry_msgs::Point32 & | p2 | ||
) | [inline] |
Get the squared distance from a 2D point to another 2D point in the XY plane.
p1 | the first point |
p2 | the second point |
Definition at line 52 of file distances.h.
double cloud_geometry::distances::pointToPointXZDistance | ( | const geometry_msgs::Point32 & | p1, |
const geometry_msgs::Point32 & | p2 | ||
) | [inline] |
Get the distance from a 2D point to another 2D point in the XZ plane.
p1 | the first point |
p2 | the second point |
Definition at line 85 of file distances.h.
double cloud_geometry::distances::pointToPointXZDistanceSqr | ( | const geometry_msgs::Point32 & | p1, |
const geometry_msgs::Point32 & | p2 | ||
) | [inline] |
Get the squared distance from a 2D point to another 2D point in the XZ plane.
p1 | the first point |
p2 | the second point |
Definition at line 74 of file distances.h.
double cloud_geometry::distances::pointToPointYZDistance | ( | const geometry_msgs::Point32 & | p1, |
const geometry_msgs::Point32 & | p2 | ||
) | [inline] |
Get the distance from a 2D point to another 2D point in the YZ plane.
p1 | the first point |
p2 | the second point |
Definition at line 107 of file distances.h.
double cloud_geometry::distances::pointToPointYZDistanceSqr | ( | const geometry_msgs::Point32 & | p1, |
const geometry_msgs::Point32 & | p2 | ||
) | [inline] |
Get the squared distance from a 2D point to another 2D point in the YZ plane.
p1 | the first point |
p2 | the second point |
Definition at line 96 of file distances.h.
double cloud_geometry::distances::pointToPolygonDistance | ( | const geometry_msgs::Point32 & | p, |
const geometry_msgs::Polygon & | poly | ||
) | [inline] |
Get the distance from a point to a 3D Polygon.
p | a point |
poly | the polygon |
Definition at line 386 of file distances.h.
double cloud_geometry::distances::pointToPolygonDistanceSqr | ( | const geometry_msgs::Point32 & | p, |
const geometry_msgs::Polygon & | poly | ||
) | [inline] |
Get the squared distance from a point to a 3D Polygon.
p | a point |
poly | the polygon |
Definition at line 335 of file distances.h.
double cloud_geometry::distances::pointToSphereDistance | ( | const geometry_msgs::Point32 & | p, |
const std::vector< double > & | sphere_coefficients | ||
) | [inline] |
Get the distance from a point to a sphere.
p | a point |
sphere_coefficients | the coefficients (x, y, z, R) of a sphere |
Definition at line 277 of file distances.h.
double cloud_geometry::distances::pointToSphereDistance | ( | const geometry_msgs::Point32 & | p, |
double | x, | ||
double | y, | ||
double | z, | ||
double | r | ||
) | [inline] |
Get the distance from a point to a sphere.
p | a point |
x | the x center coefficient of a sphere |
y | the y center coefficient of a sphere |
z | the z center coefficient of a sphere |
R | the radius coefficient of a sphere |
Definition at line 294 of file distances.h.