model_fitter.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2009, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 // Author(s): Marius Muja and Matei Ciocarlie
00036 
00037 #ifndef _MODEL_FITTER_H_
00038 #define _MODEL_FITTER_H_
00039 
00040 #include <string>
00041 #include <vector>
00042 #include <algorithm>
00043 
00044 #include "tf/transform_datatypes.h"
00045 
00046 #include "geometry_msgs/Point32.h"
00047 #include "sensor_msgs/PointCloud.h"
00048 #include "shape_msgs/Mesh.h"
00049 
00050 namespace distance_field {
00051   class PropagationDistanceField;
00052 }
00053 
00054 namespace tabletop_object_detector {
00055 
00057 
00063 class ModelFitInfo {
00064  private:
00066   int model_id_;
00068   geometry_msgs::Pose fit_pose_;
00070   float score_;
00071 
00072  public:
00074   ModelFitInfo(int model_id, const geometry_msgs::Pose &pose, float score) : model_id_(model_id), 
00075     fit_pose_(pose), score_(score) {}
00076 
00078   int getModelId() const {return model_id_;}
00080   float getScore() const {return score_;} 
00082   geometry_msgs::Pose getPose() const {return fit_pose_;}
00083 
00085   static bool compareScores(const ModelFitInfo &mf1, const ModelFitInfo &mf2)
00086   {
00087     return mf1.score_ < mf2.score_;
00088   }  
00089 };
00090 
00092 
00099 class ModelToCloudFitter
00100 {
00101  protected:
00103   int model_id_;
00104 
00105   void sampleMesh(const shape_msgs::Mesh &mesh, std::vector<tf::Vector3> &btVectors, double resolution);
00106 
00107  public:
00108 
00110   ModelToCloudFitter() : model_id_(-1) {}
00112   virtual ~ModelToCloudFitter(){}
00113 
00115   void setModelId(int id){model_id_=id;}
00117   int getModelId() const {return model_id_;}
00118 
00119   //----------------------------------------------------------------
00120   // Be sure to define these functions if you define your new awesome fitter:
00121   //----------------------------------------------------------------
00122 
00124   // void initializeFromMesh(const shape_msgs::Mesh &mesh) {}
00125 
00127   // template <class PointCloudType>
00128   //  ModelFitInfo fitPointCloud(const PointCloudType &cloud);
00129 };
00130 
00132 
00135 class DistanceFieldFitter : public ModelToCloudFitter
00136 {
00137  protected:
00139   distance_field::PropagationDistanceField* distance_voxel_grid_;
00141   double distance_field_resolution_;
00143 
00144   float truncate_value_;
00145 
00147   void initializeFromBtVectors(const std::vector<tf::Vector3> &points);
00148 
00149  public:
00151   DistanceFieldFitter();
00153   ~DistanceFieldFitter();
00154   
00156   void initializeFromMesh(const shape_msgs::Mesh &mesh);
00157 };
00158 
00159 } //namespace tabletop_object_detector
00160 
00161 #endif


tabletop_object_detector
Author(s): Marius Muja and Matei Ciocarlie
autogenerated on Mon Oct 6 2014 11:45:30