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 #ifndef LOCALIZATION_H_
00033 #define LOCALIZATION_H_
00034
00035
00036 #include <iostream>
00037 #include <math.h>
00038 #include <set>
00039 #include <string>
00040 #include <time.h>
00041
00042
00043 #include <pcl/filters/extract_indices.h>
00044 #include <pcl/filters/voxel_grid.h>
00045 #include <pcl/io/pcd_io.h>
00046 #include <pcl/point_types.h>
00047 #include <pcl/segmentation/sac_segmentation.h>
00048
00049
00050 #include <agile_grasp/grasp_hypothesis.h>
00051 #include <agile_grasp/hand_search.h>
00052 #include <agile_grasp/handle.h>
00053 #include <agile_grasp/handle_search.h>
00054 #include <agile_grasp/learning.h>
00055 #include <agile_grasp/plot.h>
00056
00057 typedef pcl::PointCloud<pcl::PointXYZ> PointCloud;
00058
00059
00068 class Localization
00069 {
00070 public:
00071
00075 Localization() : num_threads_(1), plots_hands_(true),
00076 plots_camera_sources_(false), cloud_(new PointCloud)
00077 { }
00078
00085 Localization(int num_threads, bool filters_boundaries, bool plots_hands) :
00086 num_threads_(num_threads), filters_boundaries_(filters_boundaries),
00087 plots_hands_(plots_hands), plots_camera_sources_(false),
00088 cloud_(new PointCloud)
00089 { }
00090
00098 std::vector<Handle> findHandles(const std::vector<GraspHypothesis>& hand_list, int min_inliers,
00099 double min_length, bool is_plotting = false);
00100
00106 std::vector<GraspHypothesis> predictAntipodalHands(const std::vector<GraspHypothesis>& hand_list,
00107 const std::string& svm_filename);
00108
00117 std::vector<GraspHypothesis> localizeHands(const PointCloud::Ptr& cloud_in, int size_left,
00118 const std::vector<int>& indices, bool calculates_antipodal, bool uses_clustering);
00119
00128 std::vector<GraspHypothesis> localizeHands(const std::string& pcd_filename_left,
00129 const std::string& pcd_filename_right, bool calculates_antipodal = false,
00130 bool uses_clustering = false);
00131
00141 std::vector<GraspHypothesis> localizeHands(const std::string& pcd_filename_left,
00142 const std::string& pcd_filename_right, const std::vector<int>& indices,
00143 bool calculates_antipodal = false, bool uses_clustering = false);
00144
00150 void setCameraTransforms(const Eigen::Matrix4d& cam_tf_left, const Eigen::Matrix4d& cam_tf_right)
00151 {
00152 cam_tf_left_ = cam_tf_left;
00153 cam_tf_right_ = cam_tf_right;
00154 }
00155
00161 const Eigen::Matrix4d& getCameraTransform(bool is_left)
00162 {
00163 if (is_left)
00164 return cam_tf_left_;
00165 else
00166 return cam_tf_right_;
00167 }
00168
00173 void setWorkspace(const Eigen::VectorXd& workspace)
00174 {
00175 workspace_ = workspace;
00176 }
00177
00182 void setNumSamples(int num_samples)
00183 {
00184 num_samples_ = num_samples;
00185 }
00186
00191 void setNeighborhoodRadiusHands(double nn_radius_hands)
00192 {
00193 nn_radius_hands_ = nn_radius_hands;
00194 }
00195
00200 void setNeighborhoodRadiusTaubin(double nn_radius_taubin)
00201 {
00202 nn_radius_taubin_ = nn_radius_taubin;
00203 }
00204
00209 void setFingerWidth(double finger_width)
00210 {
00211 finger_width_ = finger_width;
00212 }
00213
00218 void setHandDepth(double hand_depth)
00219 {
00220 hand_depth_ = hand_depth;
00221 }
00222
00227 void setHandOuterDiameter(double hand_outer_diameter)
00228 {
00229 hand_outer_diameter_ = hand_outer_diameter;
00230 }
00231
00236 void setInitBite(double init_bite)
00237 {
00238 init_bite_ = init_bite;
00239 }
00240
00245 void setHandHeight(double hand_height)
00246 {
00247 hand_height_ = hand_height;
00248 }
00249
00250 private:
00251
00255 struct UniqueVectorComparator
00256 {
00263 bool operator ()(const Eigen::Vector3i& a, const Eigen::Vector3i& b)
00264 {
00265 for (int i = 0; i < a.size(); i++)
00266 {
00267 if (a(i) != b(i))
00268 {
00269 return a(i) < b(i);
00270 }
00271 }
00272
00273 return false;
00274 }
00275 };
00276
00285 void voxelizeCloud(const PointCloud::Ptr& cloud_in, const Eigen::VectorXi& pts_cam_source_in,
00286 PointCloud::Ptr& cloud_out, Eigen::VectorXi& pts_cam_source_out, double cell_size);
00287
00296 void filterWorkspace(const PointCloud::Ptr& cloud_in, const Eigen::VectorXi& pts_cam_source_in,
00297 PointCloud::Ptr& cloud_out, Eigen::VectorXi& pts_cam_source_out);
00298
00304 std::vector<GraspHypothesis> filterHands(const std::vector<GraspHypothesis>& hand_list);
00305
00311 Eigen::Vector3i floorVector(const Eigen::Vector3d& a);
00312
00313 Plot plot_;
00314 Eigen::Matrix4d cam_tf_left_, cam_tf_right_;
00315 Eigen::VectorXd workspace_;
00316 Eigen::Matrix3Xd cloud_normals_;
00317 PointCloud::Ptr cloud_;
00318 int num_threads_;
00319 int num_samples_;
00320 double nn_radius_taubin_;
00321 double nn_radius_hands_;
00322 double finger_width_;
00323 double hand_outer_diameter_;
00324 double hand_depth_;
00325 double hand_height_;
00326 double init_bite_;
00327 bool plots_camera_sources_;
00328 bool plots_hands_;
00329 bool filters_boundaries_;
00330 };
00331
00332 #endif