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
00033
00034
00038 #ifndef FCL_BROAD_PHASE_DYNAMIC_AABB_TREE_H
00039 #define FCL_BROAD_PHASE_DYNAMIC_AABB_TREE_H
00040
00041 #include "fcl/broadphase/broadphase.h"
00042 #include "fcl/broadphase/hierarchy_tree.h"
00043 #include "fcl/BV/BV.h"
00044 #include "fcl/shape/geometric_shapes_utility.h"
00045 #include <boost/unordered_map.hpp>
00046 #include <boost/bind.hpp>
00047 #include <limits>
00048
00049
00050 namespace fcl
00051 {
00052
00053 class DynamicAABBTreeCollisionManager : public BroadPhaseCollisionManager
00054 {
00055 public:
00056 typedef NodeBase<AABB> DynamicAABBNode;
00057 typedef boost::unordered_map<CollisionObject*, DynamicAABBNode*> DynamicAABBTable;
00058
00059 int max_tree_nonbalanced_level;
00060 int tree_incremental_balance_pass;
00061 int& tree_topdown_balance_threshold;
00062 int& tree_topdown_level;
00063 int tree_init_level;
00064
00065 bool octree_as_geometry_collide;
00066 bool octree_as_geometry_distance;
00067
00068
00069 DynamicAABBTreeCollisionManager() : tree_topdown_balance_threshold(dtree.bu_threshold),
00070 tree_topdown_level(dtree.topdown_level)
00071 {
00072 max_tree_nonbalanced_level = 10;
00073 tree_incremental_balance_pass = 10;
00074 tree_topdown_balance_threshold = 2;
00075 tree_topdown_level = 0;
00076 tree_init_level = 0;
00077 setup_ = false;
00078
00079
00080 octree_as_geometry_collide = true;
00081 octree_as_geometry_distance = false;
00082 }
00083
00085 void registerObjects(const std::vector<CollisionObject*>& other_objs);
00086
00088 void registerObject(CollisionObject* obj);
00089
00091 void unregisterObject(CollisionObject* obj);
00092
00094 void setup();
00095
00097 void update();
00098
00100 void update(CollisionObject* updated_obj);
00101
00103 void update(const std::vector<CollisionObject*>& updated_objs);
00104
00106 void clear()
00107 {
00108 dtree.clear();
00109 table.clear();
00110 }
00111
00113 void getObjects(std::vector<CollisionObject*>& objs) const
00114 {
00115 objs.resize(this->size());
00116 std::transform(table.begin(), table.end(), objs.begin(), boost::bind(&DynamicAABBTable::value_type::first, _1));
00117 }
00118
00120 void collide(CollisionObject* obj, void* cdata, CollisionCallBack callback) const;
00121
00123 void distance(CollisionObject* obj, void* cdata, DistanceCallBack callback) const;
00124
00126 void collide(void* cdata, CollisionCallBack callback) const;
00127
00129 void distance(void* cdata, DistanceCallBack callback) const;
00130
00132 void collide(BroadPhaseCollisionManager* other_manager_, void* cdata, CollisionCallBack callback) const;
00133
00135 void distance(BroadPhaseCollisionManager* other_manager_, void* cdata, DistanceCallBack callback) const;
00136
00138 bool empty() const
00139 {
00140 return dtree.empty();
00141 }
00142
00144 size_t size() const
00145 {
00146 return dtree.size();
00147 }
00148
00149 const HierarchyTree<AABB>& getTree() const { return dtree; }
00150
00151
00152 private:
00153 HierarchyTree<AABB> dtree;
00154 boost::unordered_map<CollisionObject*, DynamicAABBNode*> table;
00155
00156 bool setup_;
00157
00158 void update_(CollisionObject* updated_obj);
00159 };
00160
00161
00162
00163 }
00164
00165 #endif