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
00038
00039
00040
00041
00042
00043
00044
00045
00046 #ifndef PCL_RECOGNITION_HYPOTHESIS_H_
00047 #define PCL_RECOGNITION_HYPOTHESIS_H_
00048
00049 #include <pcl/recognition/ransac_based/model_library.h>
00050 #include <pcl/recognition/ransac_based/auxiliary.h>
00051
00052 namespace pcl
00053 {
00054 namespace recognition
00055 {
00056 class HypothesisBase
00057 {
00058 public:
00059 HypothesisBase (const ModelLibrary::Model* obj_model)
00060 : obj_model_ (obj_model)
00061 {}
00062
00063 HypothesisBase (const ModelLibrary::Model* obj_model, const float* rigid_transform)
00064 : obj_model_ (obj_model)
00065 {
00066 memcpy (rigid_transform_, rigid_transform, 12*sizeof (float));
00067 }
00068
00069 virtual ~HypothesisBase (){}
00070
00071 void
00072 setModel (const ModelLibrary::Model* model)
00073 {
00074 obj_model_ = model;
00075 }
00076
00077 public:
00078 float rigid_transform_[12];
00079 const ModelLibrary::Model* obj_model_;
00080 };
00081
00082 class Hypothesis: public HypothesisBase
00083 {
00084 public:
00085 Hypothesis (const ModelLibrary::Model* obj_model = NULL)
00086 : HypothesisBase (obj_model),
00087 match_confidence_ (-1.0f),
00088 linear_id_ (-1)
00089 {
00090 }
00091
00092 Hypothesis (const Hypothesis& src)
00093 : HypothesisBase (src.obj_model_, src.rigid_transform_),
00094 match_confidence_ (src.match_confidence_),
00095 explained_pixels_ (src.explained_pixels_)
00096 {
00097 }
00098
00099 virtual ~Hypothesis (){}
00100
00101 const Hypothesis&
00102 operator =(const Hypothesis& src)
00103 {
00104 memcpy (this->rigid_transform_, src.rigid_transform_, 12*sizeof (float));
00105 this->obj_model_ = src.obj_model_;
00106 this->match_confidence_ = src.match_confidence_;
00107 this->explained_pixels_ = src.explained_pixels_;
00108
00109 return *this;
00110 }
00111
00112 void
00113 setLinearId (int id)
00114 {
00115 linear_id_ = id;
00116 }
00117
00118 int
00119 getLinearId () const
00120 {
00121 return (linear_id_);
00122 }
00123
00124 void
00125 computeBounds (float bounds[6]) const
00126 {
00127 const float *b = obj_model_->getBoundsOfOctreePoints ();
00128 float p[3];
00129
00130
00131 aux::transform (rigid_transform_, b[0], b[2], b[4], p);
00132 bounds[0] = bounds[1] = p[0];
00133 bounds[2] = bounds[3] = p[1];
00134 bounds[4] = bounds[5] = p[2];
00135
00136
00137 aux::transform (rigid_transform_, b[0], b[2], b[5], p); aux::expandBoundingBoxToContainPoint (bounds, p);
00138 aux::transform (rigid_transform_, b[0], b[3], b[4], p); aux::expandBoundingBoxToContainPoint (bounds, p);
00139 aux::transform (rigid_transform_, b[0], b[3], b[5], p); aux::expandBoundingBoxToContainPoint (bounds, p);
00140 aux::transform (rigid_transform_, b[1], b[2], b[4], p); aux::expandBoundingBoxToContainPoint (bounds, p);
00141 aux::transform (rigid_transform_, b[1], b[2], b[5], p); aux::expandBoundingBoxToContainPoint (bounds, p);
00142 aux::transform (rigid_transform_, b[1], b[3], b[4], p); aux::expandBoundingBoxToContainPoint (bounds, p);
00143 aux::transform (rigid_transform_, b[1], b[3], b[5], p); aux::expandBoundingBoxToContainPoint (bounds, p);
00144 }
00145
00146 void
00147 computeCenterOfMass (float center_of_mass[3]) const
00148 {
00149 aux::transform (rigid_transform_, obj_model_->getOctreeCenterOfMass (), center_of_mass);
00150 }
00151
00152 public:
00153 float match_confidence_;
00154 std::set<int> explained_pixels_;
00155 int linear_id_;
00156 };
00157 }
00158 }
00159
00160 #endif