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_POINT_H_
00034 #define _CLOUD_GEOMETRY_POINT_H_
00035
00036
00037 #include <sensor_msgs/PointCloud.h>
00038 #include <geometry_msgs/Polygon.h>
00039 #include <geometry_msgs/Point32.h>
00040 #include <geometry_msgs/Point.h>
00041 #include <geometry_msgs/Vector3.h>
00042
00043 #include <Eigen/Core>
00044
00045 #include <cfloat>
00046
00047 namespace cloud_geometry
00048 {
00049
00051 struct Leaf
00052 {
00053 float centroid_x, centroid_y, centroid_z;
00054 unsigned short nr_points;
00055 };
00056
00057
00059
00064 inline bool
00065 checkPointEqual (const geometry_msgs::Point32 &p1, const geometry_msgs::Point32 &p2, double eps = 1e-10)
00066 {
00067 if (
00068 (fabs (p1.x - p2.x) < eps) && (fabs (p1.y - p2.y) < eps) && (fabs (p1.z - p2.z) < eps)
00069 )
00070 return (true);
00071 return (false);
00072 }
00073
00074 int getChannelIndex (const sensor_msgs::PointCloud &points, std::string channel_name);
00075 int getChannelIndex (sensor_msgs::PointCloudConstPtr points, std::string channel_name);
00076
00078
00083 inline void
00084 getPointAsFloatArray (const sensor_msgs::PointCloud &points, int index, std::vector<float> &array)
00085 {
00086
00087 if (array.size () != 3 + points.get_channels_size ())
00088 array.resize (3 + points.get_channels_size ());
00089 array[0] = points.points[index].x;
00090 array[1] = points.points[index].y;
00091 array[2] = points.points[index].z;
00092
00093 for (unsigned int d = 0; d < points.get_channels_size (); d++)
00094 array[3 + d] = points.channels[d].values[index];
00095 }
00096
00098
00104 inline void
00105 getPointAsFloatArray (const sensor_msgs::PointCloud &points, int index, std::vector<float> &array, int nr_channels)
00106 {
00107
00108 if ((int)array.size () != 3 + nr_channels)
00109 array.resize (3 + nr_channels);
00110 array[0] = points.points[index].x;
00111 array[1] = points.points[index].y;
00112 array[2] = points.points[index].z;
00113
00114 for (int d = 0; d < nr_channels; d++)
00115 array[3 + d] = points.channels[d].values[index];
00116 }
00117
00119
00126 inline void
00127 getPointAsFloatArray (const sensor_msgs::PointCloud &points, int index, std::vector<float> &array, int start_channel, int end_channel)
00128 {
00129
00130 if ((int)array.size () != 3 + end_channel - start_channel)
00131 array.resize (3 + end_channel - start_channel);
00132 array[0] = points.points[index].x;
00133 array[1] = points.points[index].y;
00134 array[2] = points.points[index].z;
00135
00136 for (int d = start_channel; d < end_channel; d++)
00137 array[3 + d - start_channel] = points.channels[d].values[index];
00138 }
00139
00141
00148 inline void
00149 getPointAsFloatArray (const sensor_msgs::PointCloud &points, int index, std::vector<float> &array, std::vector<int> channels)
00150 {
00151 if (channels.size () > points.get_channels_size ())
00152 return;
00153
00154 if (array.size () != 3 + channels.size ())
00155 array.resize (3 + channels.size ());
00156 array[0] = points.points[index].x;
00157 array[1] = points.points[index].y;
00158 array[2] = points.points[index].z;
00159
00160 for (unsigned int d = 0; d < channels.size (); d++)
00161 array[3 + d] = points.channels[channels.at (d)].values[index];
00162 }
00163
00165
00169 inline geometry_msgs::Point32
00170 cross (const geometry_msgs::Point32 &p1, const geometry_msgs::Point32 &p2)
00171 {
00172 geometry_msgs::Point32 r;
00173 r.x = p1.y * p2.z - p1.z * p2.y;
00174 r.y = p1.z * p2.x - p1.x * p2.z;
00175 r.z = p1.x * p2.y - p1.y * p2.x;
00176 return (r);
00177 }
00178
00180
00184 inline geometry_msgs::Point32
00185 cross (const std::vector<double> &p1, const geometry_msgs::Point32 &p2)
00186 {
00187 geometry_msgs::Point32 r;
00188 r.x = p1.at (1) * p2.z - p1.at (2) * p2.y;
00189 r.y = p1.at (2) * p2.x - p1.at (0) * p2.z;
00190 r.z = p1.at (0) * p2.y - p1.at (1) * p2.x;
00191 return (r);
00192 }
00193
00195
00199 inline geometry_msgs::Point32
00200 cross (const geometry_msgs::Point32 &p1, const std::vector<double> &p2)
00201 {
00202 geometry_msgs::Point32 r;
00203 r.x = p2.at (1) * p1.z - p2.at (2) * p1.y;
00204 r.y = p2.at (2) * p1.x - p2.at (0) * p1.z;
00205 r.z = p2.at (0) * p1.y - p2.at (1) * p1.x;
00206 return (r);
00207 }
00208
00210
00215 inline void
00216 cross (const std::vector<double> &p1, const std::vector<double> &p2, std::vector<double> &p3)
00217 {
00218 if (p3.size () != 3)
00219 p3.resize (3);
00220 p3[0] = p1.at (1) * p2.at (2) - p1.at (2) * p2.at (1);
00221 p3[1] = p1.at (2) * p2.at (0) - p1.at (0) * p2.at (2);
00222 p3[2] = p1.at (0) * p2.at (1) - p1.at (1) * p2.at (0);
00223 }
00224
00226
00230 inline double
00231 dot (const geometry_msgs::Point32 &p1, const geometry_msgs::Point32 &p2)
00232 {
00233 return (p1.x * p2.x + p1.y * p2.y + p1.z * p2.z);
00234 }
00235
00237
00241 inline double
00242 dot (const geometry_msgs::Point &p1, const geometry_msgs::Point &p2)
00243 {
00244 return (p1.x * p2.x + p1.y * p2.y + p1.z * p2.z);
00245 }
00246
00248
00252 inline double
00253 dot (const geometry_msgs::Point32 &p1, const geometry_msgs::Point &p2)
00254 {
00255 return (p1.x * p2.x + p1.y * p2.y + p1.z * p2.z);
00256 }
00257
00259
00263 inline double
00264 dot (const geometry_msgs::Point &p1, const geometry_msgs::Point32 &p2)
00265 {
00266 return (p1.x * p2.x + p1.y * p2.y + p1.z * p2.z);
00267 }
00268
00270
00274 inline double
00275 dot (const geometry_msgs::Point32 &p1, const geometry_msgs::Vector3 &p2)
00276 {
00277 return (p1.x * p2.x + p1.y * p2.y + p1.z * p2.z);
00278 }
00279
00281
00285 inline double
00286 dot (const geometry_msgs::Vector3 &p1, const geometry_msgs::Point32 &p2)
00287 {
00288 return (p1.x * p2.x + p1.y * p2.y + p1.z * p2.z);
00289 }
00290
00292
00296 inline double
00297 dot (const geometry_msgs::Vector3 &p1, const geometry_msgs::Vector3 &p2)
00298 {
00299 return (p1.x * p2.x + p1.y * p2.y + p1.z * p2.z);
00300 }
00301
00303
00307 inline double
00308 dot (const std::vector<double> &p1, const std::vector<double> &p2)
00309 {
00310 return (p1.at (0) * p2.at (0) + p1.at (1) * p2.at (1) + p1.at (2) * p2.at (2));
00311 }
00312
00314
00318 inline void
00319 normalizePoint (const geometry_msgs::Point32 &p, geometry_msgs::Point32 &q)
00320 {
00321
00322 double n_norm = sqrt (p.x * p.x + p.y * p.y + p.z * p.z);
00323 q.x = p.x / n_norm;
00324 q.y = p.y / n_norm;
00325 q.z = p.z / n_norm;
00326 }
00327
00329
00332 inline void
00333 normalizePoint (geometry_msgs::Point32 &p)
00334 {
00335 normalizePoint (p, p);
00336 }
00337
00338 void getPointIndicesAxisParallelNormals (const sensor_msgs::PointCloud &points, int nx, int ny, int nz, double eps_angle,
00339 const geometry_msgs::Point32 &axis, std::vector<int> &indices);
00340 void getPointIndicesAxisPerpendicularNormals (const sensor_msgs::PointCloud &points, int nx, int ny, int nz, double eps_angle,
00341 const geometry_msgs::Point32 &axis, std::vector<int> &indices);
00342
00343 void downsamplePointCloud (const sensor_msgs::PointCloud &points, const std::vector<int> &indices, sensor_msgs::PointCloud &points_down, geometry_msgs::Point leaf_size,
00344 std::vector<Leaf> &leaves, int d_idx, double cut_distance = DBL_MAX);
00345
00346 void downsamplePointCloud (const sensor_msgs::PointCloud &points, sensor_msgs::PointCloud &points_down, geometry_msgs::Point leaf_size,
00347 std::vector<Leaf> &leaves, int d_idx, double cut_distance = DBL_MAX);
00348
00349 void downsamplePointCloud (sensor_msgs::PointCloudConstPtr points, sensor_msgs::PointCloud &points_down, geometry_msgs::Point leaf_size,
00350 std::vector<Leaf> &leaves, int d_idx, double cut_distance = DBL_MAX);
00351
00352 void downsamplePointCloud (const sensor_msgs::PointCloud &points, sensor_msgs::PointCloud &points_down, geometry_msgs::Point leaf_size);
00353
00355
00360 inline void
00361 getCoordinateSystemOnPlane (const std::vector<double> &plane_coeff, Eigen::Vector3d &u, Eigen::Vector3d &v)
00362 {
00363
00364 u (1) = 0;
00365 if (fabs (plane_coeff.at (0)) != 1)
00366 {
00367 u (0) = 1;
00368 u (2) = 0;
00369 }
00370 else
00371 {
00372 u (0) = 0;
00373 u (2) = 1;
00374 }
00375
00376
00377 v (0) = plane_coeff.at (1) * u (2) - plane_coeff.at (2) * u (1);
00378 v (1) = plane_coeff.at (2) * u (0) - plane_coeff.at (0) * u (2);
00379 v (2) = plane_coeff.at (0) * u (1) - plane_coeff.at (1) * u (0);
00380 double v_length = sqrt (v (0) * v (0) + v (1) * v (1) + v (2) * v (2));
00381 v (0) /= v_length;
00382 v (1) /= v_length;
00383 v (2) /= v_length;
00384
00385
00386 u (0) = v (1) * plane_coeff.at (2) - v (2) * plane_coeff.at (1);
00387 u (1) = v (2) * plane_coeff.at (0) - v (0) * plane_coeff.at (2);
00388 u (2) = v (0) * plane_coeff.at (1) - v (1) * plane_coeff.at (0);
00389 double u_length = sqrt (u (0) * u (0) + u (1) * u (1) + u (2) * u (2));
00390 u (0) /= u_length;
00391 u (1) /= u_length;
00392 u (2) /= u_length;
00393 }
00394
00395 std::string getAvailableChannels (const sensor_msgs::PointCloud &cloud);
00396 std::string getAvailableChannels (const sensor_msgs::PointCloudConstPtr& cloud);
00397
00398 void getPointCloud (const sensor_msgs::PointCloud &input, const std::vector<int> &indices, sensor_msgs::PointCloud &output);
00399 void getPointCloudOutside (const sensor_msgs::PointCloud &input, std::vector<int> indices, sensor_msgs::PointCloud &output);
00400
00402
00405 inline void
00406 cerr_p (const geometry_msgs::Point32 &p)
00407 {
00408 std::cerr << p.x << " " << p.y << " " << p.z << std::endl;
00409 }
00410 inline void
00411 cerr_p (const std::vector<double> &p)
00412 {
00413 for (unsigned int i = 0; i < p.size () - 1; i++)
00414 std::cerr << p[i] << " ";
00415 std::cerr << p[p.size () - 1] << std::endl;
00416 }
00417
00419
00422 inline void
00423 cerr_poly (const geometry_msgs::Polygon &poly)
00424 {
00425 for (unsigned int i = 0; i < poly.points.size (); i++)
00426 {
00427 std::cerr << poly.points[i].x << " " << poly.points[i].y << " " << poly.points[i].z << std::endl;
00428 }
00429 }
00430
00431 }
00432
00433 #endif