BVH_model.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2011, 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 Willow Garage, Inc. 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 
00037 #ifndef FCL_BVH_MODEL_H
00038 #define FCL_BVH_MODEL_H
00039 
00040 #include "fcl/collision_object.h"
00041 #include "fcl/BVH/BVH_internal.h"
00042 #include "fcl/BV/BV_node.h"
00043 #include "fcl/BVH/BV_splitter.h"
00044 #include "fcl/BVH/BV_fitter.h"
00045 #include <vector>
00046 #include <boost/shared_ptr.hpp>
00047 
00048 namespace fcl
00049 {
00050 
00052 template<typename BV>
00053 class BVHModel : public CollisionGeometry
00054 {
00055 
00056 public:
00058   BVHModelType getModelType() const
00059   {
00060     if(num_tris && num_vertices)
00061       return BVH_MODEL_TRIANGLES;
00062     else if(num_vertices)
00063       return BVH_MODEL_POINTCLOUD;
00064     else
00065       return BVH_MODEL_UNKNOWN;
00066   }
00067 
00069   BVHModel() : vertices(NULL),
00070                tri_indices(NULL),
00071                prev_vertices(NULL),
00072                num_tris(0),
00073                num_vertices(0),
00074                build_state(BVH_BUILD_STATE_EMPTY),
00075                bv_splitter(new BVSplitter<BV>(SPLIT_METHOD_MEAN)),
00076                bv_fitter(new BVFitter<BV>()),
00077                num_tris_allocated(0),
00078                num_vertices_allocated(0),
00079                num_bvs_allocated(0),
00080                num_vertex_updated(0),
00081                primitive_indices(NULL),
00082                bvs(NULL),
00083                num_bvs(0)
00084   {
00085   }
00086 
00088   BVHModel(const BVHModel& other);
00089 
00091   ~BVHModel()
00092   {
00093     delete [] vertices;
00094     delete [] tri_indices;
00095     delete [] bvs;
00096 
00097     delete [] prev_vertices;
00098     delete [] primitive_indices;
00099   }
00100 
00102   
00104   const BVNode<BV>& getBV(int id) const
00105   {
00106     return bvs[id];
00107   }
00108 
00110   BVNode<BV>& getBV(int id)
00111   {
00112     return bvs[id];
00113   }
00114 
00116   int getNumBVs() const
00117   {
00118     return num_bvs;
00119   }
00120 
00122   OBJECT_TYPE getObjectType() const { return OT_BVH; }
00123 
00125   NODE_TYPE getNodeType() const { return BV_UNKNOWN; }
00126 
00128   void computeLocalAABB();
00129 
00131   int beginModel(int num_tris = 0, int num_vertices = 0);
00132 
00134   int addVertex(const Vec3f& p);
00135 
00137   int addTriangle(const Vec3f& p1, const Vec3f& p2, const Vec3f& p3);
00138 
00140   int addSubModel(const std::vector<Vec3f>& ps, const std::vector<Triangle>& ts);
00141 
00143   int addSubModel(const std::vector<Vec3f>& ps);
00144 
00146   int endModel();
00147 
00148 
00150   int beginReplaceModel();
00151 
00153   int replaceVertex(const Vec3f& p);
00154 
00156   int replaceTriangle(const Vec3f& p1, const Vec3f& p2, const Vec3f& p3);
00157 
00159   int replaceSubModel(const std::vector<Vec3f>& ps);
00160 
00162   int endReplaceModel(bool refit = true, bool bottomup = true);
00163 
00164 
00167   int beginUpdateModel();
00168 
00170   int updateVertex(const Vec3f& p);
00171 
00173   int updateTriangle(const Vec3f& p1, const Vec3f& p2, const Vec3f& p3);
00174 
00176   int updateSubModel(const std::vector<Vec3f>& ps);
00177 
00179   int endUpdateModel(bool refit = true, bool bottomup = true);
00180 
00182   int memUsage(int msg) const;
00183 
00186   void makeParentRelative()
00187   {
00188     Vec3f I[3] = {Vec3f(1, 0, 0), Vec3f(0, 1, 0), Vec3f(0, 0, 1)};
00189     makeParentRelativeRecurse(0, I, Vec3f());
00190   }
00191 
00192 public:
00194   Vec3f* vertices;
00195 
00197   Triangle* tri_indices;
00198 
00200   Vec3f* prev_vertices;
00201 
00203   int num_tris;
00204 
00206   int num_vertices;
00207 
00209   BVHBuildState build_state;
00210 
00212   boost::shared_ptr<BVSplitterBase<BV> > bv_splitter;
00213 
00215   boost::shared_ptr<BVFitterBase<BV> > bv_fitter;
00216 
00217 private:
00218 
00219   int num_tris_allocated;
00220   int num_vertices_allocated;
00221   int num_bvs_allocated;
00222   int num_vertex_updated; 
00223   unsigned int* primitive_indices;
00224 
00225 
00227   BVNode<BV>* bvs;
00228 
00230   int num_bvs;
00231 
00233   int buildTree();
00234 
00236   int refitTree(bool bottomup);
00237 
00239   int refitTree_topdown();
00240 
00242   int refitTree_bottomup();
00243 
00245   int recursiveBuildTree(int bv_id, int first_primitive, int num_primitives);
00246 
00248   int recursiveRefitTree_bottomup(int bv_id);
00249 
00252   void makeParentRelativeRecurse(int bv_id, Vec3f parent_axis[], const Vec3f& parent_c)
00253   {
00254     if(!bvs[bv_id].isLeaf())
00255     {
00256       makeParentRelativeRecurse(bvs[bv_id].first_child, parent_axis, bvs[bv_id].getCenter());
00257 
00258       makeParentRelativeRecurse(bvs[bv_id].first_child + 1, parent_axis, bvs[bv_id].getCenter());
00259     }
00260 
00261     bvs[bv_id].bv = translate(bvs[bv_id].bv, -parent_c);
00262   }
00263 };
00264 
00265 
00266 template<>
00267 void BVHModel<OBB>::makeParentRelativeRecurse(int bv_id, Vec3f parent_axis[], const Vec3f& parent_c);
00268 
00269 template<>
00270 void BVHModel<RSS>::makeParentRelativeRecurse(int bv_id, Vec3f parent_axis[], const Vec3f& parent_c);
00271 
00272 template<>
00273 void BVHModel<OBBRSS>::makeParentRelativeRecurse(int bv_id, Vec3f parent_axis[], const Vec3f& parent_c);
00274 
00275 
00277 template<>
00278 NODE_TYPE BVHModel<AABB>::getNodeType() const;
00279 
00280 template<>
00281 NODE_TYPE BVHModel<OBB>::getNodeType() const;
00282 
00283 template<>
00284 NODE_TYPE BVHModel<RSS>::getNodeType() const;
00285 
00286 template<>
00287 NODE_TYPE BVHModel<kIOS>::getNodeType() const;
00288 
00289 template<>
00290 NODE_TYPE BVHModel<OBBRSS>::getNodeType() const;
00291 
00292 template<>
00293 NODE_TYPE BVHModel<KDOP<16> >::getNodeType() const;
00294 
00295 template<>
00296 NODE_TYPE BVHModel<KDOP<18> >::getNodeType() const;
00297 
00298 template<>
00299 NODE_TYPE BVHModel<KDOP<24> >::getNodeType() const;
00300 
00301 }
00302 
00303 #endif
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


fcl
Author(s): Jia Pan
autogenerated on Tue Jan 15 2013 16:05:30