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
00037 #ifndef PCL_FEATURES_IMPL_SHOT_LRF_H_
00038 #define PCL_FEATURES_IMPL_SHOT_LRF_H_
00039
00040 #include <utility>
00041 #include <pcl/features/shot_lrf.h>
00042
00044
00045 template<typename PointInT, typename PointOutT> float
00046 pcl::SHOTLocalReferenceFrameEstimation<PointInT, PointOutT>::getLocalRF (const int& current_point_idx, Eigen::Matrix3f &rf)
00047 {
00048 const Eigen::Vector4f& central_point = (*input_)[current_point_idx].getVector4fMap ();
00049 std::vector<int> n_indices;
00050 std::vector<float> n_sqr_distances;
00051
00052 this->searchForNeighbors (current_point_idx, search_parameter_, n_indices, n_sqr_distances);
00053
00054 Eigen::Matrix<double, Eigen::Dynamic, 4> vij (n_indices.size (), 4);
00055
00056 Eigen::Matrix3d cov_m = Eigen::Matrix3d::Zero ();
00057
00058 double distance = 0.0;
00059 double sum = 0.0;
00060
00061 int valid_nn_points = 0;
00062
00063 for (size_t i_idx = 0; i_idx < n_indices.size (); ++i_idx)
00064 {
00065 Eigen::Vector4f pt = surface_->points[n_indices[i_idx]].getVector4fMap ();
00066 if (pt.head<3> () == central_point.head<3> ())
00067 continue;
00068
00069
00070 vij.row (valid_nn_points) = (pt - central_point).cast<double> ();
00071 vij (valid_nn_points, 3) = 0;
00072
00073 distance = search_parameter_ - sqrt (n_sqr_distances[i_idx]);
00074
00075
00076 cov_m += distance * (vij.row (valid_nn_points).head<3> ().transpose () * vij.row (valid_nn_points).head<3> ());
00077
00078 sum += distance;
00079 valid_nn_points++;
00080 }
00081
00082 if (valid_nn_points < 5)
00083 {
00084
00085 rf.setConstant (std::numeric_limits<float>::quiet_NaN ());
00086
00087 return (std::numeric_limits<float>::max ());
00088 }
00089
00090 cov_m /= sum;
00091
00092 Eigen::SelfAdjointEigenSolver<Eigen::Matrix3d> solver (cov_m);
00093
00094 const double& e1c = solver.eigenvalues ()[0];
00095 const double& e2c = solver.eigenvalues ()[1];
00096 const double& e3c = solver.eigenvalues ()[2];
00097
00098 if (!pcl_isfinite (e1c) || !pcl_isfinite (e2c) || !pcl_isfinite (e3c))
00099 {
00100
00101 rf.setConstant (std::numeric_limits<float>::quiet_NaN ());
00102
00103 return (std::numeric_limits<float>::max ());
00104 }
00105
00106
00107 Eigen::Vector4d v1 = Eigen::Vector4d::Zero ();
00108 Eigen::Vector4d v3 = Eigen::Vector4d::Zero ();
00109 v1.head<3> () = solver.eigenvectors ().col (2);
00110 v3.head<3> () = solver.eigenvectors ().col (0);
00111
00112 int plusNormal = 0, plusTangentDirection1=0;
00113 for (int ne = 0; ne < valid_nn_points; ne++)
00114 {
00115 double dp = vij.row (ne).dot (v1);
00116 if (dp >= 0)
00117 plusTangentDirection1++;
00118
00119 dp = vij.row (ne).dot (v3);
00120 if (dp >= 0)
00121 plusNormal++;
00122 }
00123
00124
00125 plusTangentDirection1 = 2*plusTangentDirection1 - valid_nn_points;
00126 if (plusTangentDirection1 == 0)
00127 {
00128 int points = 5;
00129 int medianIndex = valid_nn_points/2;
00130
00131 for (int i = -points/2; i <= points/2; i++)
00132 if ( vij.row (medianIndex - i).dot (v1) > 0)
00133 plusTangentDirection1 ++;
00134
00135 if (plusTangentDirection1 < points/2+1)
00136 v1 *= - 1;
00137 } else if (plusTangentDirection1 < 0)
00138 v1 *= - 1;
00139
00140
00141 plusNormal = 2*plusNormal - valid_nn_points;
00142 if (plusNormal == 0)
00143 {
00144 int points = 5;
00145 int medianIndex = valid_nn_points/2;
00146
00147 for (int i = -points/2; i <= points/2; i++)
00148 if ( vij.row (medianIndex - i).dot (v3) > 0)
00149 plusNormal ++;
00150
00151 if (plusNormal < points/2+1)
00152 v3 *= - 1;
00153 } else if (plusNormal < 0)
00154 v3 *= - 1;
00155
00156 rf.row (0) = v1.head<3> ().cast<float> ();
00157 rf.row (2) = v3.head<3> ().cast<float> ();
00158 rf.row (1) = rf.row (2).cross (rf.row (0));
00159
00160 return (0.0f);
00161 }
00162
00163 template <typename PointInT, typename PointOutT> void
00164 pcl::SHOTLocalReferenceFrameEstimation<PointInT, PointOutT>::computeFeature (PointCloudOut &output)
00165 {
00166
00167 if (this->getKSearch () != 0)
00168 {
00169 PCL_ERROR(
00170 "[pcl::%s::computeFeature] Error! Search method set to k-neighborhood. Call setKSearch(0) and setRadiusSearch( radius ) to use this class.\n",
00171 getClassName().c_str ());
00172 return;
00173 }
00174 tree_->setSortedResults (true);
00175
00176 for (size_t i = 0; i < indices_->size (); ++i)
00177 {
00178
00179 Eigen::Matrix3f rf;
00180 PointOutT& output_rf = output[i];
00181
00182
00183
00184 if (getLocalRF ((*indices_)[i], rf) == std::numeric_limits<float>::max ())
00185 {
00186 output.is_dense = false;
00187 }
00188
00189 output_rf.x_axis.getNormalVector3fMap () = rf.row (0);
00190 output_rf.y_axis.getNormalVector3fMap () = rf.row (1);
00191 output_rf.z_axis.getNormalVector3fMap () = rf.row (2);
00192 }
00193
00194 }
00195
00196 template <typename PointInT, typename PointOutT> void
00197 pcl::SHOTLocalReferenceFrameEstimation<PointInT, PointOutT>::computeFeatureEigen (pcl::PointCloud<Eigen::MatrixXf> &output)
00198 {
00199
00200 if (this->getKSearch () != 0)
00201 {
00202 PCL_ERROR(
00203 "[pcl::%s::computeFeatureEigen] Error! Search method set to k-neighborhood. Call setKSearch(0) and setRadiusSearch( radius ) to use this class.\n",
00204 getClassName().c_str ());
00205 return;
00206 }
00207 tree_->setSortedResults (true);
00208
00209
00210 output.channels["shot_lrf"].name = "shot_lrf";
00211 output.channels["shot_lrf"].offset = 0;
00212 output.channels["shot_lrf"].size = 4;
00213 output.channels["shot_lrf"].count = 9;
00214 output.channels["shot_lrf"].datatype = sensor_msgs::PointField::FLOAT32;
00215
00216
00217 output.points.resize (indices_->size (), 9);
00218 for (size_t i = 0; i < indices_->size (); ++i)
00219 {
00220
00221 Eigen::Matrix3f rf;
00222
00223
00224
00225 if (getLocalRF ((*indices_)[i], rf) == std::numeric_limits<float>::max ())
00226 {
00227 output.is_dense = false;
00228 }
00229
00230 output.points.block<1, 3> (i, 0) = rf.row (0);
00231 output.points.block<1, 3> (i, 3) = rf.row (1);
00232 output.points.block<1, 3> (i, 6) = rf.row (2);
00233 }
00234
00235 }
00236
00237 #define PCL_INSTANTIATE_SHOTLocalReferenceFrameEstimation(T,OutT) template class PCL_EXPORTS pcl::SHOTLocalReferenceFrameEstimation<T,OutT>;
00238
00239 #endif // PCL_FEATURES_IMPL_SHOT_LRF_H_
00240