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 
00035 
00036 #define BOOST_PARAMETER_MAX_ARITY 7
00037 
00038 #include "jsk_recognition_utils/geo/plane.h"
00039 #include "jsk_recognition_utils/geo_util.h"
00040 #include "jsk_recognition_utils/pcl_conversion_util.h"
00041 
00042 namespace jsk_recognition_utils
00043 {
00044   Plane::Plane(const std::vector<float>& coefficients)
00045   {
00046     normal_ = Eigen::Vector3f(coefficients[0], coefficients[1], coefficients[2]);
00047     d_ = coefficients[3] / normal_.norm();
00048     normal_.normalize();
00049     initializeCoordinates();
00050   }
00051 
00052   Plane::Plane(const boost::array<float, 4>& coefficients)
00053   {
00054     normal_ = Eigen::Vector3f(coefficients[0], coefficients[1], coefficients[2]);
00055     d_ = coefficients[3] / normal_.norm();
00056     normal_.normalize();
00057     initializeCoordinates();
00058   }
00059 
00060   Plane::Plane(Eigen::Vector3f normal, double d) :
00061     normal_(normal.normalized()), d_(d / normal.norm())
00062   {
00063     initializeCoordinates();
00064   }
00065   
00066   Plane::Plane(Eigen::Vector3f normal, Eigen::Vector3f p) :
00067     normal_(normal.normalized()), d_(- normal.dot(p) / normal.norm())
00068   {
00069     initializeCoordinates();
00070   }
00071           
00072   
00073   Plane::~Plane()
00074   {
00075 
00076   }
00077   
00078   Eigen::Vector3f Plane::getPointOnPlane()
00079   {
00080     Eigen::Vector3f x = normal_ / (normal_.norm() * normal_.norm()) * (- d_);
00081     return x;
00082   }
00083 
00084   Plane Plane::flip()
00085   {
00086     return Plane(- normal_, - d_);
00087   }
00088 
00089   Plane::Ptr Plane::faceToOrigin()
00090   {
00091     Eigen::Vector3f p = getPointOnPlane();
00092     Eigen::Vector3f n = getNormal();
00093     
00094     if (p.dot(n) < 0) {
00095       return Plane::Ptr (new Plane(normal_, d_));
00096     }
00097     else {
00098       return Plane::Ptr (new Plane(- normal_, - d_));
00099     }
00100   }
00101 
00102   bool Plane::isSameDirection(const Plane& another)
00103   {
00104     return isSameDirection(another.normal_);
00105   }
00106   
00107   bool Plane::isSameDirection(const Eigen::Vector3f& another_normal)
00108   {
00109     return normal_.dot(another_normal) > 0;
00110   }
00111   
00112   double Plane::signedDistanceToPoint(const Eigen::Vector3f p)
00113   {
00114     return (normal_.dot(p) + d_);
00115   }
00116   
00117   double Plane::signedDistanceToPoint(const Eigen::Vector4f p)
00118   {
00119     return signedDistanceToPoint(Eigen::Vector3f(p[0], p[1], p[2]));
00120   }
00121   
00122   double Plane::distanceToPoint(const Eigen::Vector4f p)
00123   {
00124     return fabs(signedDistanceToPoint(p));
00125   }
00126 
00127   double Plane::distanceToPoint(const Eigen::Vector3f p)
00128   {
00129     return fabs(signedDistanceToPoint(p));
00130   }
00131   
00132   double Plane::distance(const Plane& another)
00133   {
00134     return fabs(fabs(d_) - fabs(another.d_));
00135   }
00136 
00137   double Plane::angle(const Eigen::Vector3f& vector)
00138   {
00139     double dot = normal_.dot(vector);
00140     if (dot > 1.0) {
00141       dot = 1.0;
00142     }
00143     else if (dot < -1.0) {
00144       dot = -1.0;
00145     }
00146     double theta = acos(dot);
00147     if (theta > M_PI / 2.0) {
00148       return M_PI - theta;
00149     }
00150 
00151     return acos(dot);
00152   }
00153   
00154   double Plane::angle(const Plane& another)
00155   {
00156     double dot = normal_.dot(another.normal_);
00157     if (dot > 1.0) {
00158       dot = 1.0;
00159     }
00160     else if (dot < -1.0) {
00161       dot = -1.0;
00162     }
00163     double theta = acos(dot);
00164     if (theta > M_PI / 2.0) {
00165       return M_PI - theta;
00166     }
00167 
00168     return acos(dot);
00169   }
00170 
00171   void Plane::project(const Eigen::Vector3f& p, Eigen::Vector3f& output)
00172   {
00173     
00174     
00175     double alpha = p.dot(normal_) + d_;
00176     
00177     output = p - alpha * normal_;
00178   }
00179 
00180   void Plane::project(const Eigen::Vector3d& p, Eigen::Vector3d& output)
00181   {
00182     Eigen::Vector3f output_f;
00183     project(Eigen::Vector3f(p[0], p[1], p[2]), output_f);
00184     pointFromVectorToVector<Eigen::Vector3f, Eigen::Vector3d>(output_f, output);
00185   }
00186 
00187   void Plane::project(const Eigen::Vector3d& p, Eigen::Vector3f& output)
00188   {
00189     project(Eigen::Vector3f(p[0], p[1], p[2]), output);
00190   }
00191 
00192   void Plane::project(const Eigen::Vector3f& p, Eigen::Vector3d& output)
00193   {
00194     Eigen::Vector3f output_f;
00195     project(p, output);
00196     pointFromVectorToVector<Eigen::Vector3f, Eigen::Vector3d>(output_f, output);
00197   }
00198 
00199   void Plane::project(const Eigen::Affine3d& pose, Eigen::Affine3d& output)
00200   {
00201     Eigen::Affine3f pose_f, output_f;
00202     convertEigenAffine3(pose, pose_f);
00203     project(pose_f, output_f);
00204     convertEigenAffine3(output_f, output);
00205   }
00206 
00207   void Plane::project(const Eigen::Affine3f& pose, Eigen::Affine3f& output)
00208   {
00209     Eigen::Vector3f p(pose.translation());
00210     Eigen::Vector3f output_p;
00211     project(p, output_p);
00212     Eigen::Quaternionf rot;
00213     rot.setFromTwoVectors(pose.rotation() * Eigen::Vector3f::UnitZ(),
00214                           coordinates().rotation() * Eigen::Vector3f::UnitZ());
00215     output = Eigen::Affine3f::Identity() * Eigen::Translation3f(output_p) * rot;
00216   }
00217 
00218   Plane Plane::transform(const Eigen::Affine3f& transform)
00219   {
00220     Eigen::Affine3d transform_d;
00221     convertEigenAffine3(transform, transform_d);
00222     return this->transform(transform_d);
00223   }
00224   
00225   Plane Plane::transform(const Eigen::Affine3d& transform)
00226   {
00227     Eigen::Vector4d n;
00228     n[0] = normal_[0];
00229     n[1] = normal_[1];
00230     n[2] = normal_[2];
00231     n[3] = d_;
00232     Eigen::Matrix4d m = transform.matrix();
00233     Eigen::Vector4d n_d = m.transpose() * n;
00234     
00235     Eigen::Vector4d n_dd = n_d / sqrt(n_d[0] * n_d[0] + n_d[1] * n_d[1] + n_d[2] * n_d[2]);
00236     return Plane(Eigen::Vector3f(n_dd[0], n_dd[1], n_dd[2]), n_dd[3]);
00237   }
00238   
00239   std::vector<float> Plane::toCoefficients()
00240   {
00241     std::vector<float> ret;
00242     toCoefficients(ret);
00243     return ret;
00244   }
00245 
00246   void Plane::toCoefficients(std::vector<float>& output)
00247   {
00248     output.push_back(normal_[0]);
00249     output.push_back(normal_[1]);
00250     output.push_back(normal_[2]);
00251     output.push_back(d_);
00252   }
00253 
00254   Eigen::Vector3f Plane::getNormal()
00255   {
00256     return normal_;
00257   }
00258 
00259   double Plane::getD() 
00260   {
00261     return d_;
00262   }
00263 
00264   void Plane::initializeCoordinates()
00265   {
00266     Eigen::Quaternionf rot;
00267     rot.setFromTwoVectors(Eigen::Vector3f::UnitZ(), normal_);
00268     double c = normal_[2];
00269     double z = 0.0;
00270     
00271     
00272     if (c == 0.0) {             
00273       z = 0.0;
00274     }
00275     else {
00276       z = - d_ / c;
00277     }
00278     plane_coordinates_
00279       = Eigen::Affine3f::Identity() * Eigen::Translation3f(0, 0, z) * rot;
00280   }
00281   
00282   Eigen::Affine3f Plane::coordinates()
00283   {
00284     return plane_coordinates_;
00285   }
00286 
00287 }