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