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_OMP_H_
00038 #define PCL_FEATURES_IMPL_SHOT_LRF_OMP_H_
00039
00040 #include <utility>
00041 #include <pcl/features/shot_lrf_omp.h>
00042 #include <pcl/features/shot_lrf.h>
00043
00044 template<typename PointInT, typename PointOutT>
00045 void
00046 pcl::SHOTLocalReferenceFrameEstimationOMP<PointInT, PointOutT>::computeFeature (PointCloudOut &output)
00047 {
00048 if (threads_ < 0)
00049 threads_ = 1;
00050
00051
00052 if (this->getKSearch () != 0)
00053 {
00054 PCL_ERROR(
00055 "[pcl::%s::computeFeature] Error! Search method set to k-neighborhood. Call setKSearch(0) and setRadiusSearch( radius ) to use this class.\n",
00056 getClassName().c_str ());
00057 return;
00058 }
00059 tree_->setSortedResults (true);
00060
00061 int data_size = static_cast<int> (indices_->size ());
00062 #pragma omp parallel for num_threads(threads_)
00063 for (int i = 0; i < data_size; ++i)
00064 {
00065
00066 Eigen::Matrix3f rf;
00067 PointOutT& output_rf = output[i];
00068
00069
00070
00071
00072 std::vector<int> n_indices;
00073 std::vector<float> n_sqr_distances;
00074 this->searchForNeighbors ((*indices_)[i], search_parameter_, n_indices, n_sqr_distances);
00075 if (getLocalRF ((*indices_)[i], rf) == std::numeric_limits<float>::max ())
00076 {
00077 output.is_dense = false;
00078 }
00079
00080 output_rf.x_axis.getNormalVector3fMap () = rf.row (0);
00081 output_rf.y_axis.getNormalVector3fMap () = rf.row (1);
00082 output_rf.z_axis.getNormalVector3fMap () = rf.row (2);
00083 }
00084
00085 }
00086
00087 template<typename PointInT, typename PointOutT>
00088 void
00089 pcl::SHOTLocalReferenceFrameEstimationOMP<PointInT, PointOutT>::computeFeatureEigen (pcl::PointCloud<Eigen::MatrixXf> &output)
00090 {
00091 if (threads_ < 0)
00092 threads_ = 1;
00093
00094
00095 if (this->getKSearch () != 0)
00096 {
00097 PCL_ERROR(
00098 "[pcl::%s::computeFeatureEigen] Error! Search method set to k-neighborhood. Call setKSearch(0) and setRadiusSearch( radius ) to use this class.\n",
00099 getClassName().c_str ());
00100 return;
00101 }
00102 tree_->setSortedResults (true);
00103
00104 int data_size = static_cast<int> (indices_->size ());
00105
00106
00107 output.channels["shot_lrf"].name = "shot_lrf";
00108 output.channels["shot_lrf"].offset = 0;
00109 output.channels["shot_lrf"].size = 4;
00110 output.channels["shot_lrf"].count = 9;
00111 output.channels["shot_lrf"].datatype = sensor_msgs::PointField::FLOAT32;
00112
00113
00114 output.points.resize (data_size, 9);
00115
00116 #pragma omp parallel for num_threads(threads_)
00117 for (int i = 0; i < data_size; ++i)
00118 {
00119
00120 Eigen::Matrix3f rf;
00121
00122
00123
00124 if (getLocalRF ((*indices_)[i], rf) == std::numeric_limits<float>::max ())
00125 {
00126 output.is_dense = false;
00127 }
00128
00129 output.points.block<1, 3> (i, 0) = rf.row (0);
00130 output.points.block<1, 3> (i, 3) = rf.row (1);
00131 output.points.block<1, 3> (i, 6) = rf.row (2);
00132 }
00133
00134 }
00135
00136 #define PCL_INSTANTIATE_SHOTLocalReferenceFrameEstimationOMP(T,OutT) template class PCL_EXPORTS pcl::SHOTLocalReferenceFrameEstimationOMP<T,OutT>;
00137
00138 #endif // PCL_FEATURES_IMPL_SHOT_LRF_H_