23 #ifndef B2_DYNAMIC_TREE_H 24 #define B2_DYNAMIC_TREE_H 30 #define b2_nullNode (-1) 78 int32 CreateProxy(
const b2AABB& aabb,
void* userData);
81 void DestroyProxy(
int32 proxyId);
91 void* GetUserData(
int32 proxyId)
const;
93 bool WasMoved(
int32 proxyId)
const;
94 void ClearMoved(
int32 proxyId);
101 template <
typename T>
102 void Query(T* callback,
const b2AABB& aabb)
const;
111 template <
typename T>
115 void Validate()
const;
119 int32 GetHeight()
const;
123 int32 GetMaxBalance()
const;
126 float GetAreaRatio()
const;
129 void RebuildBottomUp();
134 void ShiftOrigin(
const b2Vec2& newOrigin);
138 int32 AllocateNode();
139 void FreeNode(
int32 node);
141 void InsertLeaf(
int32 node);
142 void RemoveLeaf(
int32 node);
146 int32 ComputeHeight()
const;
149 void ValidateStructure(
int32 index)
const;
150 void ValidateMetrics(
int32 index)
const;
165 b2Assert(0 <= proxyId && proxyId < m_nodeCapacity);
166 return m_nodes[proxyId].userData;
171 b2Assert(0 <= proxyId && proxyId < m_nodeCapacity);
172 return m_nodes[proxyId].moved;
177 b2Assert(0 <= proxyId && proxyId < m_nodeCapacity);
178 m_nodes[proxyId].moved =
false;
183 b2Assert(0 <= proxyId && proxyId < m_nodeCapacity);
184 return m_nodes[proxyId].aabb;
187 template <
typename T>
207 bool proceed = callback->QueryCallback(nodeId);
208 if (proceed ==
false)
222 template <
typename T>
243 b2Vec2 t = p1 + maxFraction * (p2 - p1);
271 if (separation > 0.0
f)
279 subInput.
p1 = input.
p1;
280 subInput.
p2 = input.
p2;
283 float value = callback->RayCastCallback(subInput, nodeId);
295 b2Vec2 t = p1 + maxFraction * (p2 - p1);
float b2Dot(const b2Vec2 &a, const b2Vec2 &b)
Perform the dot product on two vectors.
b2Vec2 lowerBound
the lower vertex
b2AABB aabb
Enlarged AABB.
B2_API bool b2TestOverlap(const b2Shape *shapeA, int32 indexA, const b2Shape *shapeB, int32 indexB, const b2Transform &xfA, const b2Transform &xfB)
Determine if two generic shapes overlap.
geometry_msgs::TransformStamped t
b2Vec2 GetCenter() const
Get the center of the AABB.
bool WasMoved(int32 proxyId) const
void RayCast(T *callback, const b2RayCastInput &input) const
const b2AABB & GetFatAABB(int32 proxyId) const
Get the fat AABB for a proxy.
float LengthSquared() const
void ClearMoved(int32 proxyId)
void * GetUserData(int32 proxyId) const
float b2Cross(const b2Vec2 &a, const b2Vec2 &b)
Perform the cross product on two vectors. In 2D this produces a scalar.
void Push(const T &element)
void Query(T *callback, const b2AABB &aabb) const
A node in the dynamic tree. The client does not interact with this directly.
An axis aligned bounding box.
float Normalize()
Convert this vector into a unit vector. Returns the length.
b2Vec2 GetExtents() const
Get the extents of the AABB (half-widths).
b2Vec2 upperBound
the upper vertex