88 float numerator =
b2Dot(normal, v1 - p1);
94 float denominator =
b2Dot(normal, d);
96 if (denominator == 0.0
f)
101 float t = numerator / denominator;
112 float rr =
b2Dot(r, r);
118 float s =
b2Dot(q - v1, r) / rr;
119 if (s < 0.0
f || 1.0
f < s)
125 if (numerator > 0.0
f)
155 massData->
mass = 0.0f;
float mass
The mass of the shape, usually in kilograms.
b2Vec2 b2Mul(const b2Mat22 &A, const b2Vec2 &v)
float b2Dot(const b2Vec2 &a, const b2Vec2 &b)
Perform the dot product on two vectors.
b2Vec2 lowerBound
the lower vertex
void ComputeMass(b2MassData *massData, float density) const override
b2Vec2 m_vertex0
Optional adjacent vertices. These are used for smooth collision.
void ComputeAABB(b2AABB *aabb, const b2Transform &transform, int32 childIndex) const override
b2Vec2 center
The position of the shape's centroid relative to the shape's origin.
geometry_msgs::TransformStamped t
void SetTwoSided(const b2Vec2 &v1, const b2Vec2 &v2)
Set this as an isolated edge. Collision is two-sided.
void SetOneSided(const b2Vec2 &v0, const b2Vec2 &v1, const b2Vec2 &v2, const b2Vec2 &v3)
bool RayCast(b2RayCastOutput *output, const b2RayCastInput &input, const b2Transform &transform, int32 childIndex) const override
Implement b2Shape.
void * Allocate(int32 size)
Allocate memory. This will use b2Alloc if the size is larger than b2_maxBlockSize.
bool TestPoint(const b2Transform &transform, const b2Vec2 &p) const override
float I
The rotational inertia of the shape about the local origin.
An axis aligned bounding box.
b2Vec2 b2MulT(const b2Mat22 &A, const b2Vec2 &v)
b2Vec2 m_vertex1
These are the edge vertices.
b2Shape * Clone(b2BlockAllocator *allocator) const override
Implement b2Shape.
float Normalize()
Convert this vector into a unit vector. Returns the length.
bool m_oneSided
Uses m_vertex0 and m_vertex3 to create smooth collision.
int32 GetChildCount() const override
This holds the mass data computed for a shape.
b2Vec2 upperBound
the upper vertex