00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00033 #ifndef _CLOUD_GEOMETRY_PROJECTIONS_H_
00034 #define _CLOUD_GEOMETRY_PROJECTIONS_H_
00035
00036
00037 #include <geometry_msgs/Point32.h>
00038 #include <geometry_msgs/Polygon.h>
00039
00040 namespace cloud_geometry
00041 {
00042
00043 namespace projections
00044 {
00045
00047
00052 inline void
00053 pointToPlane (const geometry_msgs::Point32 &p, geometry_msgs::Point32 &q, const std::vector<double> &plane_coefficients)
00054 {
00055 double distance = plane_coefficients.at (0) * p.x +
00056 plane_coefficients.at (1) * p.y +
00057 plane_coefficients.at (2) * p.z +
00058 plane_coefficients.at (3);
00059
00060 q.x = p.x - distance * plane_coefficients.at (0);
00061 q.y = p.y - distance * plane_coefficients.at (1);
00062 q.z = p.z - distance * plane_coefficients.at (2);
00063 }
00064
00066
00071 inline void
00072 pointsToPlane (const geometry_msgs::Polygon &p, geometry_msgs::Polygon &q, const std::vector<double> &plane_coefficients)
00073 {
00074 q.points.resize (p.points.size ());
00075 for (unsigned int i = 0; i < p.points.size (); i++)
00076 pointToPlane (p.points[i], q.points[i], plane_coefficients);
00077 }
00078
00080
00085 inline void
00086 pointsToPlane (sensor_msgs::PointCloud &p, const std::vector<int> &indices, const std::vector<double> &plane_coefficients)
00087 {
00088 for (unsigned int i = 0; i < indices.size (); i++)
00089 pointToPlane (p.points[indices.at (i)], p.points[indices.at (i)], plane_coefficients);
00090 }
00091
00093
00099 inline void
00100 pointsToPlane (const sensor_msgs::PointCloud &p, const std::vector<int> &indices, sensor_msgs::PointCloud &q, const std::vector<double> &plane_coefficients)
00101 {
00102 q.points.resize (indices.size ());
00103 for (unsigned int i = 0; i < indices.size (); i++)
00104 pointToPlane (p.points[indices.at (i)], q.points[i], plane_coefficients);
00105 }
00106
00108
00114 inline void
00115 pointToPlane (const geometry_msgs::Point32 &p, geometry_msgs::Point32 &q, const std::vector<double> &plane_coefficients,
00116 double &distance)
00117 {
00118 distance = plane_coefficients.at (0) * p.x +
00119 plane_coefficients.at (1) * p.y +
00120 plane_coefficients.at (2) * p.z +
00121 plane_coefficients.at (3);
00122
00123 q.x = p.x - distance * plane_coefficients.at (0);
00124 q.y = p.y - distance * plane_coefficients.at (1);
00125 q.z = p.z - distance * plane_coefficients.at (2);
00126 }
00127
00128 }
00129 }
00130
00131 #endif