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
00037
00038
00039 #ifndef PCL_FEATURES_IMPL_PPF_H_
00040 #define PCL_FEATURES_IMPL_PPF_H_
00041
00042 #include <pcl/features/ppf.h>
00043 #include <pcl/features/pfh.h>
00044
00046 template <typename PointInT, typename PointNT, typename PointOutT>
00047 pcl::PPFEstimation<PointInT, PointNT, PointOutT>::PPFEstimation ()
00048 : FeatureFromNormals <PointInT, PointNT, PointOutT> ()
00049 {
00050 feature_name_ = "PPFEstimation";
00051
00052 Feature<PointInT, PointOutT>::tree_.reset (new pcl::search::KdTree <PointInT> ());
00053 Feature<PointInT, PointOutT>::search_radius_ = 1.0f;
00054 }
00055
00056
00058 template <typename PointInT, typename PointNT, typename PointOutT> void
00059 pcl::PPFEstimation<PointInT, PointNT, PointOutT>::computeFeature (PointCloudOut &output)
00060 {
00061
00062 output.points.resize (indices_->size () * input_->points.size ());
00063 output.height = 1;
00064 output.width = static_cast<uint32_t> (output.points.size ());
00065 output.is_dense = true;
00066
00067
00068 for (size_t index_i = 0; index_i < indices_->size (); ++index_i)
00069 {
00070 size_t i = (*indices_)[index_i];
00071 for (size_t j = 0 ; j < input_->points.size (); ++j)
00072 {
00073 PointOutT p;
00074 if (i != j)
00075 {
00076 if (
00077 pcl::computePairFeatures (input_->points[i].getVector4fMap (),
00078 normals_->points[i].getNormalVector4fMap (),
00079 input_->points[j].getVector4fMap (),
00080 normals_->points[j].getNormalVector4fMap (),
00081 p.f1, p.f2, p.f3, p.f4))
00082 {
00083
00084 Eigen::Vector3f model_reference_point = input_->points[i].getVector3fMap (),
00085 model_reference_normal = normals_->points[i].getNormalVector3fMap (),
00086 model_point = input_->points[j].getVector3fMap ();
00087 Eigen::AngleAxisf rotation_mg (acosf (model_reference_normal.dot (Eigen::Vector3f::UnitX ())),
00088 model_reference_normal.cross (Eigen::Vector3f::UnitX ()).normalized ());
00089 Eigen::Affine3f transform_mg = Eigen::Translation3f ( rotation_mg * ((-1) * model_reference_point)) * rotation_mg;
00090
00091 Eigen::Vector3f model_point_transformed = transform_mg * model_point;
00092 float angle = atan2f ( -model_point_transformed(2), model_point_transformed(1));
00093 if (sin (angle) * model_point_transformed(2) < 0.0f)
00094 angle *= (-1);
00095 p.alpha_m = -angle;
00096 }
00097 else
00098 {
00099 PCL_ERROR ("[pcl::%s::computeFeature] Computing pair feature vector between points %zu and %zu went wrong.\n", getClassName ().c_str (), i, j);
00100 p.f1 = p.f2 = p.f3 = p.f4 = p.alpha_m = std::numeric_limits<float>::quiet_NaN ();
00101 output.is_dense = false;
00102 }
00103 }
00104
00105
00106 else
00107 {
00108 p.f1 = p.f2 = p.f3 = p.f4 = p.alpha_m = std::numeric_limits<float>::quiet_NaN ();
00109 output.is_dense = false;
00110 }
00111
00112 output.points[index_i*input_->points.size () + j] = p;
00113 }
00114 }
00115 }
00116
00118 template <typename PointInT, typename PointNT> void
00119 pcl::PPFEstimation<PointInT, PointNT, Eigen::MatrixXf>::computeFeatureEigen (pcl::PointCloud<Eigen::MatrixXf> &output)
00120 {
00121
00122 output.points.resize (indices_->size () * input_->points.size (), 5);
00123 output.height = 1;
00124 output.width = static_cast<uint32_t> (indices_->size () * input_->points.size ());
00125
00126 output.is_dense = true;
00127
00128 for (size_t index_i = 0; index_i < indices_->size (); ++index_i)
00129 {
00130 size_t i = (*indices_)[index_i];
00131 for (size_t j = 0 ; j < input_->points.size (); ++j)
00132 {
00133 Eigen::VectorXf p (5);
00134 if (i != j)
00135 {
00136 if (
00137 pcl::computePairFeatures (input_->points[i].getVector4fMap (),
00138 normals_->points[i].getNormalVector4fMap (),
00139 input_->points[j].getVector4fMap (),
00140 normals_->points[j].getNormalVector4fMap (),
00141 p (0), p (1), p (2), p (3)))
00142 {
00143
00144 Eigen::Vector3f model_reference_point = input_->points[i].getVector3fMap (),
00145 model_reference_normal = normals_->points[i].getNormalVector3fMap (),
00146 model_point = input_->points[j].getVector3fMap ();
00147 Eigen::AngleAxisf rotation_mg (acosf (model_reference_normal.dot (Eigen::Vector3f::UnitX ())),
00148 model_reference_normal.cross (Eigen::Vector3f::UnitX ()).normalized ());
00149 Eigen::Affine3f transform_mg = Eigen::Translation3f ( rotation_mg * ((-1) * model_reference_point)) * rotation_mg;
00150
00151 Eigen::Vector3f model_point_transformed = transform_mg * model_point;
00152 float angle = atan2f ( -model_point_transformed(2), model_point_transformed(1));
00153 if (sin (angle) * model_point_transformed(2) < 0.0f)
00154 angle *= (-1);
00155 p (4) = -angle;
00156 }
00157 else
00158 {
00159 PCL_ERROR ("[pcl::%s::computeFeature] Computing pair feature vector between points %zu and %zu went wrong.\n", getClassName ().c_str (), i, j);
00160 p.setConstant (std::numeric_limits<float>::quiet_NaN ());
00161 output.is_dense = false;
00162 }
00163 }
00164
00165
00166 else
00167 {
00168 p.setConstant (std::numeric_limits<float>::quiet_NaN ());
00169 output.is_dense = false;
00170 }
00171
00172 output.points.row (index_i*input_->points.size () + j) = p;
00173 }
00174 }
00175 }
00176
00177
00178 #define PCL_INSTANTIATE_PPFEstimation(T,NT,OutT) template class PCL_EXPORTS pcl::PPFEstimation<T,NT,OutT>;
00179
00180
00181 #endif // PCL_FEATURES_IMPL_PPF_H_