Go to the documentation of this file.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 
00031 
00032 
00033 
00034 #ifndef cpl_comp_geometry_h_DEFINED
00035 #define cpl_comp_geometry_h_DEFINED
00036 
00037 #include <ros/ros.h>
00038 #include <pcl16/point_cloud.h>
00039 #include <pcl16/point_types.h>
00040 #include <geometry_msgs/PointStamped.h>
00041 
00042 namespace cpl_visual_features
00043 {
00044 
00045 bool lineSegmentIntersection2D(pcl16::PointXYZ a1, pcl16::PointXYZ a2, pcl16::PointXYZ b1, pcl16::PointXYZ b2,
00046                                pcl16::PointXYZ& intersection);
00047 
00048 bool lineLineIntersection2D(pcl16::PointXYZ a1, pcl16::PointXYZ a2, pcl16::PointXYZ b1, pcl16::PointXYZ b2,
00049                             pcl16::PointXYZ& intersection);
00050 
00051 bool pointIsBetweenOthers(pcl16::PointXYZ& pt, pcl16::PointXYZ& x1, pcl16::PointXYZ& x2);
00052 
00053 double pointLineDistance2D(pcl16::PointXYZ& pt, pcl16::PointXYZ& a, pcl16::PointXYZ& b);
00054 
00055 static inline double dist(pcl16::PointXYZ a, pcl16::PointXYZ b)
00056 {
00057   const double dx = a.x-b.x;
00058   const double dy = a.y-b.y;
00059   const double dz = a.z-b.z;
00060   return std::sqrt(dx*dx+dy*dy+dz*dz);
00061 }
00062 
00063 static inline double dist(pcl16::PointXYZ a, geometry_msgs::Point b)
00064 {
00065   const double dx = a.x-b.x;
00066   const double dy = a.y-b.y;
00067   const double dz = a.z-b.z;
00068   return std::sqrt(dx*dx+dy*dy+dz*dz);
00069 }
00070 
00071 static inline double dist(geometry_msgs::Point b, pcl16::PointXYZ a)
00072 {
00073   return dist(a,b);
00074 }
00075 
00076 static inline double sqrDist(Eigen::Vector3f& a, pcl16::PointXYZ& b)
00077 {
00078   const double dx = a[0]-b.x;
00079   const double dy = a[1]-b.y;
00080   const double dz = a[2]-b.z;
00081   return dx*dx+dy*dy+dz*dz;
00082 }
00083 
00084 
00085 static inline double sqrDist(Eigen::Vector4f& a, Eigen::Vector4f& b)
00086 {
00087   const double dx = a[0]-b[0];
00088   const double dy = a[1]-b[1];
00089   const double dz = a[2]-b[2];
00090   return dx*dx+dy*dy+dz*dz;
00091 }
00092 
00093 static inline double sqrDist(pcl16::PointXYZ a, pcl16::PointXYZ b)
00094 {
00095   const double dx = a.x-b.x;
00096   const double dy = a.y-b.y;
00097   const double dz = a.z-b.z;
00098   return dx*dx+dy*dy+dz*dz;
00099 }
00100 
00101 static inline double sqrDistXY(pcl16::PointXYZ a, pcl16::PointXYZ b)
00102 {
00103   const double dx = a.x-b.x;
00104   const double dy = a.y-b.y;
00105   return dx*dx+dy*dy;
00106 }
00107 
00108 };
00109 #endif // cpl_comp_geometry_h_DEFINED