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
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