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
00033 #ifndef _CLOUD_KDTREE_KDTREE_FLANN_H_
00034 #define _CLOUD_KDTREE_KDTREE_FLANN_H_
00035
00036 #include <cstdio>
00037
00038 #include "door_handle_detector/kdtree/kdtree.h"
00039
00040 #include <boost/thread/mutex.hpp>
00041
00042 #include <flann.h>
00043
00044 namespace cloud_kdtree
00045 {
00046 class KdTreeFLANN : public KdTree
00047 {
00048 public:
00049
00051
00054 KdTreeFLANN (const sensor_msgs::PointCloud &points)
00055 {
00056 epsilon_ = 0.0;
00057 dim_ = 3;
00058
00059
00060 nr_points_ = convertCloudToArray (points);
00061 if (nr_points_ == 0)
00062 {
00063 ROS_ERROR ("[KdTreeFLANN] Could not create kD-tree for %d points!", nr_points_);
00064 return;
00065 }
00066
00067
00068 float speedup;
00069 flann_param_.algorithm = KDTREE;
00070 flann_param_.log_level = LOG_NONE;
00071 flann_param_.log_destination = NULL;
00072
00073 flann_param_.trees = 1;
00074 flann_param_.target_precision = -1;
00075 flann_param_.checks = 128;
00076
00077 m_lock_.lock ();
00078 printf("Building index\n");
00079 index_id_ = flann_build_index (points_, nr_points_, dim_, &speedup, &flann_param_);
00080 printf("Index built\n");
00081 m_lock_.unlock ();
00082 }
00083
00085
00092 KdTreeFLANN (const sensor_msgs::PointCloud &points, const std::vector<int> &indices)
00093 {
00094 epsilon_ = 0.0;
00095 dim_ = 3;
00096
00097
00098 nr_points_ = convertCloudToArray (points, indices);
00099 if (nr_points_ == 0)
00100 {
00101 ROS_ERROR ("[KdTreeFLANN] Could not create kD-tree for %d points!", nr_points_);
00102 return;
00103 }
00104
00105
00106 float speedup;
00107 flann_param_.algorithm = KDTREE;
00108 flann_param_.log_level = LOG_NONE;
00109 flann_param_.log_destination = NULL;
00110
00111 flann_param_.trees = 1;
00112 flann_param_.target_precision = -1;
00113 flann_param_.checks = 128;
00114
00115 m_lock_.lock ();
00116 index_id_ = flann_build_index (points_, nr_points_, dim_, &speedup, &flann_param_);
00117 m_lock_.unlock ();
00118 }
00119
00121
00122 virtual ~KdTreeFLANN ()
00123 {
00124 m_lock_.lock ();
00125
00126
00127 if (points_ != NULL && nr_points_ != 0)
00128 free (points_);
00129
00130
00131 flann_free_index (index_id_, &flann_param_);
00132
00133 m_lock_.unlock ();
00134 }
00135
00136 virtual void nearestKSearch (const geometry_msgs::Point32 &p_q, int k, std::vector<int> &k_indices, std::vector<float> &k_distances);
00137 virtual void nearestKSearch (const sensor_msgs::PointCloud &points, int index, int k, std::vector<int> &k_indices, std::vector<float> &k_distances);
00138
00140
00146 virtual inline void
00147 nearestKSearch (int index, int k, std::vector<int> &k_indices, std::vector<float> &k_distances)
00148 {
00149 if (index >= nr_points_)
00150 return;
00151
00152 m_lock_.lock ();
00153 flann_find_nearest_neighbors_index (index_id_, &points_[index], 1, &k_indices[0], &k_distances[0], k, flann_param_.checks, &flann_param_);
00154 m_lock_.unlock ();
00155 return;
00156 }
00157
00158 virtual bool radiusSearch (const geometry_msgs::Point32 &p_q, double radius, std::vector<int> &k_indices, std::vector<float> &k_distances, int max_nn = INT_MAX);
00159 virtual bool radiusSearch (const sensor_msgs::PointCloud &points, int index, double radius, std::vector<int> &k_indices, std::vector<float> &k_distances, int max_nn = INT_MAX);
00160
00162
00169 virtual inline bool
00170 radiusSearch (int index, double radius, std::vector<int> &k_indices, std::vector<float> &k_distances,
00171 int max_nn = INT_MAX)
00172 {
00173 radius *= radius;
00174
00175 int neighbors_in_radius_ = flann_param_.checks;
00176
00177
00178
00179
00180 if (neighbors_in_radius_ > max_nn) neighbors_in_radius_ = max_nn;
00181 k_indices.resize (neighbors_in_radius_);
00182 k_distances.resize (neighbors_in_radius_);
00183
00184 m_lock_.lock ();
00185 int neighbors_found = flann_radius_search (index_id_, &points_[index], &k_indices[0], &k_distances[0],
00186 neighbors_in_radius_, radius, flann_param_.checks, &flann_param_);
00187 m_lock_.unlock ();
00188
00189 if (neighbors_found == 0) {
00190 return (false);
00191 }
00192
00193 k_indices.resize(neighbors_found);
00194 k_distances.resize(neighbors_found);
00195
00196 return (true);
00197 }
00198
00199 private:
00200
00201 int convertCloudToArray (const sensor_msgs::PointCloud &ros_cloud);
00202 int convertCloudToArray (const sensor_msgs::PointCloud &ros_cloud, const std::vector<int> &indices);
00203
00204 private:
00205
00206 boost::mutex m_lock_;
00207
00209 FLANN_INDEX index_id_;
00210
00212 FLANNParameters flann_param_;
00213
00215 float* points_;
00216
00218 int nr_points_;
00220 int dim_;
00221 };
00222
00223 }
00224
00225 #endif