Box2D  3.0.0
A Real-Time-Oriented 2-D Physics Engine
Classes | Typedefs | Enumerations | Functions | Variables
box2d Namespace Reference

Classes

class  AABB
 Axis Aligned Bounding Box. More...
 
class  AllocatedArray
 Allocated Array. More...
 
class  ArrayList
 Array list. More...
 
class  BlockAllocator
 Block allocator. More...
 
struct  BlockDeallocator
 Blockl Deallocator. More...
 
class  Body
 A physical entity that exists within a World. More...
 
class  BodyAtty
 An "attorney" through which a World can get special access to a Body "client". More...
 
class  BodyConstraint
 Body Constraint. More...
 
struct  BodyDef
 Body Definition. More...
 
class  BroadPhase
 Broad phase assistant. More...
 
class  ChainShape
 Chain shape. More...
 
class  CircleShape
 Circle shape. More...
 
struct  ClipVertex
 Used for computing contact manifolds. More...
 
struct  ConstraintSolverConf
 Constraint solver configuration data. More...
 
class  Contact
 A potential contact between the chidren of two Fixture objects. More...
 
class  ContactAtty
 An "attorney" through which a World can get special access to a Contact "client". More...
 
struct  ContactFeature
 Contact Feature. More...
 
class  ContactFilter
 Implement this class to provide collision filtering. In other words, you can implement this class if you want finer control over contact creation. More...
 
struct  ContactImpulses
 
class  ContactImpulsesList
 Contact Impulse. More...
 
class  ContactListener
 An interface for "listeners" for contacts. More...
 
class  DestructionListener
 Joints and fixtures are destroyed when their associated body is destroyed. Implement this listener so that you may nullify references to these joints and shapes. More...
 
struct  DistanceConf
 Distance Configuration. More...
 
class  DistanceJoint
 Distance Joint. More...
 
struct  DistanceJointDef
 Distance joint definition. This requires defining an anchor point on both bodies and the non-zero length of the distance joint. The definition uses local anchor points so that the initial configuration can violate the constraint slightly. This helps when saving and loading a game. More...
 
struct  DistanceOutput
 Distance Output. More...
 
class  DistanceProxy
 Distance Proxy. More...
 
class  DynamicTree
 A dynamic AABB tree broad-phase, inspired by Nathanael Presson's btDbvt. More...
 
class  EdgeShape
 Edge shape. More...
 
struct  Filter
 A holder for contact filtering data. More...
 
class  Fixed
 Fixed. More...
 
class  Fixture
 Fixture. More...
 
class  FixtureAtty
 Fixture Attorney. More...
 
struct  FixtureDef
 Fixture definition. More...
 
struct  FixtureProxy
 Fixture proxy. More...
 
class  FlagGuard
 
class  FrictionJoint
 Friction joint. This is used for top-down friction. It provides 2D translational friction and angular friction. More...
 
struct  FrictionJointDef
 Friction joint definition. More...
 
class  GearJoint
 A gear joint is used to connect two joints together. Either joint can be a revolute or prismatic joint. You specify a gear ratio to bind the motions together: coordinate1 + ratio * coordinate2 = constant The ratio can be negative or positive. If one joint is a revolute joint and the other joint is a prismatic joint, then the ratio will have units of length or units of 1/length. More...
 
struct  GearJointDef
 Gear joint definition. This definition requires two existing revolute or prismatic joints (any combination will work). More...
 
class  GrowableStack
 This is a growable LIFO stack with an initial capacity of N. If the stack size exceeds the initial capacity, the heap is used to increase the size of the stack. More...
 
struct  IndexPair
 Index pair. More...
 
struct  IndexPairSeparation
 Index pair separation. More...
 
struct  IndexSeparation
 Index separation. More...
 
class  InternalList
 
class  Island
 Island. More...
 
class  Joint
 Base Joint class. More...
 
class  JointAtty
 
struct  JointDef
 Abstract base Joint Definition class. More...
 
class  List
 
struct  ListNode
 
class  Manifold
 Manifold for two convex shapes. More...
 
struct  MassData
 Mass data. More...
 
struct  Mat22
 A 2-by-2 matrix. More...
 
struct  Mat33
 A 3-by-3 matrix. Stored in column-major order. More...
 
class  MotorJoint
 A motor joint is used to control the relative motion between two bodies. A typical usage is to control the movement of a dynamic body with respect to the ground. More...
 
struct  MotorJointDef
 Motor joint definition. More...
 
class  MouseJoint
 Mouse Joint. More...
 
struct  MouseJointDef
 Mouse joint definition. This requires a world target point, tuning parameters, and the time step. More...
 
struct  MovementConf
 
class  PolygonShape
 Polygon shape. More...
 
struct  Position
 Positional data structure. More...
 
struct  PositionConstraint
 Contact Position Constraint. More...
 
struct  PositionSolution
 
struct  PositionSolverManifold
 Position solver manifold. More...
 
struct  PreStepStats
 Pre-phase per-step statistics. More...
 
class  PrismaticJoint
 Prismatic Joint. More...
 
struct  PrismaticJointDef
 Prismatic joint definition. This requires defining a line of motion using an axis and an anchor point. The definition uses local anchor points and a local axis so that the initial configuration can violate the constraint slightly. The joint translation is zero when the local anchor points coincide in world space. Using local anchors and a local axis helps when saving and loading a game. More...
 
struct  Profile
 Profiling data. Times are in milliseconds. More...
 
struct  ProxyIdPair
 Proxy ID pair. More...
 
class  PulleyJoint
 The pulley joint is connected to two bodies and two fixed ground points. The pulley supports a ratio such that: length1 + ratio * length2 <= constant Yes, the force transmitted is scaled by the ratio. Warning: the pulley joint can get a bit squirrelly by itself. They often work better when combined with prismatic joints. You should also cover the the anchor points with static shapes to prevent one side from going to zero length. More...
 
struct  PulleyJointDef
 Pulley joint definition. This requires two ground anchors, two dynamic body anchor points, and a pulley ratio. More...
 
class  QueryFixtureReporter
 Callback class for AABB queries. See World::Query. More...
 
class  RaiiWrapper
 
class  RayCastFixtureReporter
 Callback class for ray casts. See World::RayCast. More...
 
struct  RayCastInput
 Ray-cast input data. More...
 
struct  RayCastOutput
 Ray-cast output data. More...
 
struct  RegStepStats
 Regular-phase per-step statistics. More...
 
class  RevoluteJoint
 Revolute Joint. More...
 
struct  RevoluteJointDef
 Revolute joint definition. This requires defining an anchor point where the bodies are joined. The definition uses local anchor points so that the initial configuration can violate the constraint slightly. You also need to specify the initial relative angle for joint limits. This helps when saving and loading a game. The local anchor points are measured from the body's origin rather than the center of mass because: More...
 
class  Rope
 
struct  RopeDef
 
class  RopeJoint
 A rope joint enforces a maximum distance between two points on two bodies. It has no other effect. Warning: if you attempt to change the maximum length during the simulation you will get some non-physical behavior. A model that would allow you to dynamically modify the length would have some sponginess, so I chose not to implement it that way. See DistanceJoint if you want to dynamically control length. More...
 
struct  RopeJointDef
 Rope joint definition. This requires two body anchor points and a maximum lengths. Note: by default the connected objects will not collide. see collideConnected in JointDef. More...
 
class  SeparationFinder
 Separation finder. More...
 
class  Shape
 Shape. More...
 
class  Simplex
 Simplex. More...
 
class  SimplexEdge
 Simplex edge. More...
 
class  Span
 
class  StackAllocator
 Stack allocator. More...
 
class  StepConf
 Step configuration. More...
 
struct  StepStats
 Per-step statistics. More...
 
class  Sweep
 Sweep. More...
 
class  Timer
 Timer for profiling. This has platform specific code and may not work on every platform. More...
 
struct  ToiConf
 Time of impact configuration. More...
 
class  TOIOutput
 TimeOfImpact Output data. More...
 
struct  ToiStepStats
 TOI-phase per-step statistics. More...
 
struct  Transformation
 Transformation. More...
 
class  UnitVec2
 
struct  Vec3
 A 2D column vector with 3 elements. More...
 
struct  Vector2D
 Vector 2D. More...
 
struct  Velocity
 Velocity related data structure. More...
 
class  VelocityConstraint
 Contact velocity constraint. More...
 
struct  Version
 Version numbering scheme. See http://en.wikipedia.org/wiki/Software_versioning. More...
 
class  VertexSet
 Vertex Set. More...
 
class  WeldJoint
 A weld joint essentially glues two bodies together. A weld joint may distort somewhat because the island constraint solver is approximate. More...
 
struct  WeldJointDef
 Weld joint definition. You need to specify local anchor points where they are attached and the relative body angle. The position of the anchor points is important for computing the reaction torque. More...
 
class  WheelJoint
 A wheel joint. This joint provides two degrees of freedom: translation along an axis fixed in bodyA and rotation in the plane. In other words, it is a point to line constraint with a rotational motor and a linear spring/damper. This joint is designed for vehicle suspensions. More...
 
struct  WheelJointDef
 Wheel joint definition. This requires defining a line of motion using an axis and an anchor point. The definition uses local anchor points and a local axis so that the initial configuration can violate the constraint slightly. The joint translation is zero when the local anchor points coincide in world space. Using local anchors and a local axis helps when saving and loading a game. More...
 
struct  Wider
 Wider. More...
 
struct  Wider< double >
 
struct  Wider< Fixed32 >
 
struct  Wider< float >
 
struct  Wider< std::int16_t >
 
struct  Wider< std::int32_t >
 
struct  Wider< std::int64_t >
 
struct  Wider< std::int8_t >
 
struct  Wider< std::uint16_t >
 
struct  Wider< std::uint32_t >
 
struct  Wider< std::uint64_t >
 
struct  Wider< std::uint8_t >
 
struct  WitnessPoints
 Witness Points. More...
 
class  World
 World. More...
 
class  WorldManifold
 World Manifold. More...
 
struct  WorldQueryWrapper
 
struct  WorldRayCastWrapper
 

Typedefs

using PointStateArray = std::array< PointState, MaxManifoldPoints >
 
using ClipList = ArrayList< ClipVertex, MaxManifoldPoints >
 Clip list for ClipSegmentToLine. More...
 
using Fixed32 = Fixed< std::int32_t, 14 >
 
using Fixed64 = Fixed< std::int64_t, 24 >
 
using RealNum = float
 Real-number type. More...
 
using Time = RealNum
 
using Frequency = RealNum
 
using Length = RealNum
 
using LinearVelocity = RealNum
 
using LinearAcceleration = RealNum
 
using Mass = RealNum
 
using InvMass = RealNum
 
using Area = RealNum
 
using Density = RealNum
 
using Angle = RealNum
 
using AngularVelocity = RealNum
 
using AngularAcceleration = RealNum
 
using Force = RealNum
 
using Torque = RealNum
 
using SecondMomentOfArea = RealNum
 
using RotInertia = RealNum
 
using InvRotInertia = RealNum
 
using Momentum = RealNum
 
using AngularMomentum = RealNum
 
using child_count_t = unsigned
 Child count type. More...
 
using size_t = std::size_t
 Size type for sizing data. More...
 
using island_count_t = size_t
 Island count type. More...
 
using ts_iters_t = std::uint8_t
 Time step iterations type. More...
 
using body_count_t = std::remove_const< decltype(MaxBodies)>::type
 Body count type. More...
 
using contact_count_t = Wider< body_count_t >::type
 Contact count type. More...
 
using joint_count_t = std::remove_const< decltype(MaxJoints)>::type
 Joint count type. More...
 
using Vec2 = Vector2D< RealNum >
 Vector 2D of RealNum. More...
 
using Length2D = Vector2D< Length >
 
using LinearVelocity2D = Vector2D< LinearVelocity >
 
using LinearAcceleration2D = Vector2D< LinearAcceleration >
 
using Force2D = Vector2D< Force >
 
using Momentum2D = Vector2D< Momentum >
 
using BodyConstraints = std::unordered_map< const Body *, BodyConstraint >
 
using PositionConstraints = std::vector< PositionConstraint >
 
using VelocityConstraints = std::vector< VelocityConstraint >
 

Enumerations

enum  PointState { PointState::NullState, PointState::AddState, PointState::PersistState, PointState::RemoveState }
 This is used for determining the state of contact points. More...
 
enum  BodyType { BodyType::Static = 0, BodyType::Kinematic, BodyType::Dynamic }
 Body Type. More...
 
enum  JointType {
  JointType::Unknown, JointType::Revolute, JointType::Prismatic, JointType::Distance,
  JointType::Pulley, JointType::Mouse, JointType::Gear, JointType::Wheel,
  JointType::Weld, JointType::Friction, JointType::Rope, JointType::Motor
}
 

Functions

template<>
constexpr AABB GetInvalid () noexcept
 
constexpr Length2D GetCenter (const AABB aabb) noexcept
 Gets the center of the AABB. More...
 
constexpr Length2D GetDimensions (const AABB aabb) noexcept
 
constexpr Length2D GetExtents (const AABB aabb) noexcept
 Gets the extents of the AABB (half-widths). More...
 
constexpr Length GetPerimeter (const AABB aabb) noexcept
 Gets the perimeter length of the AABB. More...
 
constexpr AABB GetEnclosingAABB (AABB a, AABB b)
 
constexpr AABB GetDisplacedAABB (AABB aabb, const Length2D displacement)
 
constexpr AABB GetFattenedAABB (AABB aabb, const Length amount)
 
constexpr bool operator== (const AABB lhs, const AABB rhs)
 
constexpr bool operator!= (const AABB lhs, const AABB rhs)
 
constexpr bool TestOverlap (const AABB a, const AABB b) noexcept
 
AABB ComputeAABB (const DistanceProxy &proxy, const Transformation xf)
 Given a transform, compute the associated axis aligned bounding box for a child shape. More...
 
AABB ComputeAABB (const Shape &shape, const Transformation xf)
 
AABB ComputeAABB (const Body &body)
 
AABB GetAABB (const Fixture &fixture, child_count_t childIndex) noexcept
 Gets the fixture's AABB. More...
 
constexpr bool operator== (ProxyIdPair lhs, ProxyIdPair rhs)
 
constexpr bool operator!= (ProxyIdPair lhs, ProxyIdPair rhs)
 
bool TestOverlap (const BroadPhase &bp, BroadPhase::size_type proxyIdA, BroadPhase::size_type proxyIdB)
 
Manifold CollideShapes (const DistanceProxy &shapeA, const Transformation &xfA, const DistanceProxy &shapeB, const Transformation &xfB, const Manifold::Conf conf=GetDefaultManifoldConf())
 
void GetPointStates (PointStateArray &state1, PointStateArray &state2, const Manifold &manifold1, const Manifold &manifold2)
 Computes the point states given two manifolds. The states pertain to the transition from manifold1 to manifold2. So state1 is either persist or remove while state2 is either add or persist. More...
 
ClipList ClipSegmentToLine (const ClipList &vIn, const UnitVec2 &normal, Length offset, ContactFeature::index_t indexA)
 Clipping for contact manifolds. More...
 
constexpr ContactFeature GetVertexVertexContactFeature (ContactFeature::index_t a, ContactFeature::index_t b) noexcept
 
constexpr ContactFeature GetVertexFaceContactFeature (ContactFeature::index_t a, ContactFeature::index_t b) noexcept
 
constexpr ContactFeature GetFaceVertexContactFeature (ContactFeature::index_t a, ContactFeature::index_t b) noexcept
 
constexpr ContactFeature GetFaceFaceContactFeature (ContactFeature::index_t a, ContactFeature::index_t b) noexcept
 
constexpr ContactFeature Flip (ContactFeature val) noexcept
 Flips contact features information. More...
 
constexpr bool operator== (ContactFeature lhs, ContactFeature rhs) noexcept
 
constexpr bool operator!= (ContactFeature lhs, ContactFeature rhs) noexcept
 
WitnessPoints GetWitnessPoints (const Simplex &simplex) noexcept
 Gets the witness points of the given simplex. More...
 
DistanceOutput Distance (const DistanceProxy &proxyA, const Transformation &transformA, const DistanceProxy &proxyB, const Transformation &transformB, const DistanceConf conf=DistanceConf{})
 Determines the closest points between two shapes. More...
 
DistanceProxy::size_type GetSupportIndex (const DistanceProxy &proxy, const Length2D d) noexcept
 Gets the supporting vertex index in the given direction for the given distance proxy. More...
 
DistanceProxy GetDistanceProxy (const Shape &shape, child_count_t index)
 Initialize the proxy using the given shape. More...
 
constexpr bool operator== (IndexPair lhs, IndexPair rhs)
 
constexpr bool operator!= (IndexPair lhs, IndexPair rhs)
 
constexpr Manifold::Conf GetDefaultManifoldConf () noexcept
 
bool operator== (const Manifold::Point &lhs, const Manifold::Point &rhs)
 
bool operator!= (const Manifold::Point &lhs, const Manifold::Point &rhs)
 
bool operator== (const Manifold &lhs, const Manifold &rhs)
 Equality operator. More...
 
bool operator!= (const Manifold &lhs, const Manifold &rhs)
 
template<>
constexpr bool IsValid (const Manifold &value) noexcept
 
Manifold GetManifold (const DistanceProxy &proxyA, const Transformation &transformA, const DistanceProxy &proxyB, const Transformation &transformB)
 
Length2D GetLocalPoint (const DistanceProxy &proxy, ContactFeature::Type type, ContactFeature::index_t index)
 
const char * GetName (Manifold::Type) noexcept
 
Area GetAreaOfCircle (Length radius)
 
Area GetAreaOfPolygon (Span< const Length2D > vertices)
 
SecondMomentOfArea GetPolarMoment (Span< const Length2D > vertices)
 Gets the polar moment of the area enclosed by the given vertices. More...
 
MassData GetMassData (const Length r, const Density density, const Length2D location)
 Computes the mass data for a circular shape. More...
 
MassData GetMassData (const Length r, const Density density, const Length2D v0, const Length2D v1)
 Computes the mass data for a linear shape. More...
 
MassData GetMassData (const Fixture &f)
 Computes the mass data for the given fixture. More...
 
MassData ComputeMassData (const Body &body) noexcept
 Computes the body's mass data. More...
 
RayCastOutput RayCast (const AABB &aabb, const RayCastInput &input)
 
RayCastOutput RayCast (const Fixture &f, const RayCastInput &input, child_count_t childIndex)
 Cast a ray against the shape of the given fixture. More...
 
bool IsLooped (const ChainShape &shape) noexcept
 
child_count_t GetNextIndex (const ChainShape &shape, child_count_t index) noexcept
 
Length2D GetEdge (const PolygonShape &shape, PolygonShape::vertex_count_t index)
 Gets the identified edge of the given polygon shape. More...
 
bool Validate (const PolygonShape &shape)
 Validate convexity of the given shape. More...
 
void SetAsBox (PolygonShape &shape, Length hx, Length hy, const Length2D center, Angle angle) noexcept
 Build vertices to represent an oriented box. More...
 
size_t FindLowestRightMostVertex (Span< const Length2D > vertices)
 
std::vector< Length2DGetConvexHullAsVector (Span< const Length2D > vertices)
 
PolygonShape Transform (PolygonShape value, Transformation xfm) noexcept
 
bool TestOverlap (const Shape &shapeA, child_count_t indexA, const Transformation &xfA, const Shape &shapeB, child_count_t indexB, const Transformation &xfB)
 Determine if two generic shapes overlap. More...
 
Length GetVertexRadius (const Shape &shape) noexcept
 Gets the vertex radius of the given shape (in meters). More...
 
IndexPairSeparation GetMaxSeparation (Span< const Length2D > verts1, Span< const UnitVec2 > norms1, Span< const Length2D > verts2, Length stop=MaxFloat *Meter)
 Gets the max separation information. More...
 
IndexPairSeparation GetMaxSeparation (Span< const Length2D > verts1, Span< const UnitVec2 > norms1, const Transformation &xf1, Span< const Length2D > verts2, const Transformation &xf2, Length stop=MaxFloat *Meter)
 Gets the max separation information. More...
 
Length2D GetScaledDelta (const Simplex &simplex, Simplex::size_type index)
 
BOX2D_CONSTEXPR Length2D GetClosestPoint (const Simplex &simplex)
 Gets the "closest point". More...
 
constexpr Length2D GetPointDelta (const SimplexEdge &sv)
 Gets "w". More...
 
constexpr bool operator== (const SimplexEdge &lhs, const SimplexEdge &rhs)
 
constexpr bool operator!= (const SimplexEdge &lhs, const SimplexEdge &rhs)
 
TOIOutput GetToiViaSat (const DistanceProxy &proxyA, const Sweep &sweepA, const DistanceProxy &proxyB, const Sweep &sweepB, const ToiConf conf=GetDefaultToiConf())
 Gets the time of impact for two disjoint convex sets using the Separating Axis Theorem. More...
 
constexpr auto GetDefaultToiConf ()
 
WorldManifold GetWorldManifold (const Manifold &manifold, const Transformation &xfA, const Length radiusA, const Transformation &xfB, const Length radiusB)
 Gets the world manifold for the given data. More...
 
WorldManifold GetWorldManifold (const Contact &contact)
 Gets the world manifold for the given data. More...
 
template<typename T , std::size_t S>
ArrayList< T, S > & operator+= (ArrayList< T, S > &lhs, const typename ArrayList< T, S >::data_type &rhs)
 
template<typename T , std::size_t S>
ArrayList< T, S > operator+ (ArrayList< T, S > lhs, const typename ArrayList< T, S >::data_type &rhs)
 
template<typename T >
void Delete (const T *p, BlockAllocator &allocator)
 
bool operator== (const BlockAllocator &a, const BlockAllocator &b)
 
bool operator!= (const BlockAllocator &a, const BlockAllocator &b)
 
void Dump (const World &world)
 Dump the world into the log file. More...
 
void Dump (const Body &body, size_t bodyIndex)
 Dump body to a log file. More...
 
void Dump (const Joint &joint, size_t index)
 Dump joint to the log file. More...
 
void Dump (const Fixture &fixture, size_t bodyIndex)
 Dump fixture to log file. More...
 
void Dump (const DistanceJoint &joint, size_t index)
 Dump joint to dmLog. More...
 
void Dump (const FrictionJoint &joint, size_t index)
 Dump joint to the log file. More...
 
void Dump (const GearJoint &joint, size_t index)
 
void Dump (const MotorJoint &joint, size_t index)
 
void Dump (const MouseJoint &joint, size_t index)
 
void Dump (const PrismaticJoint &joint, size_t index)
 
void Dump (const PulleyJoint &joint, size_t index)
 Dump joint to dmLog. More...
 
void Dump (const RevoluteJoint &joint, size_t index)
 
void Dump (const RopeJoint &joint, size_t index)
 
void Dump (const WeldJoint &joint, size_t index)
 
void Dump (const WheelJoint &joint, size_t index)
 
constexpr Fixed32 operator+ (Fixed32 lhs, Fixed32 rhs) noexcept
 
constexpr Fixed32 operator- (Fixed32 lhs, Fixed32 rhs) noexcept
 
constexpr Fixed32 operator* (Fixed32 lhs, Fixed32 rhs) noexcept
 
constexpr Fixed32 operator/ (Fixed32 lhs, Fixed32 rhs) noexcept
 
constexpr Fixed32 operator% (Fixed32 lhs, Fixed32 rhs) noexcept
 
constexpr bool operator== (Fixed32 lhs, Fixed32 rhs) noexcept
 
constexpr bool operator!= (Fixed32 lhs, Fixed32 rhs) noexcept
 
constexpr bool operator<= (Fixed32 lhs, Fixed32 rhs) noexcept
 
constexpr bool operator>= (Fixed32 lhs, Fixed32 rhs) noexcept
 
constexpr bool operator< (Fixed32 lhs, Fixed32 rhs) noexcept
 
constexpr bool operator> (Fixed32 lhs, Fixed32 rhs) noexcept
 
template<class TYPE >
constexpr auto Square (TYPE t) noexcept
 
template<typename T >
auto Sqrt (T t)
 
template<typename T >
auto Atan2 (T y, T x)
 
template<typename T >
constexpr T Abs (T a)
 
template<typename T >
round (T value, unsigned precision=100000)
 
template<>
float round (float value, uint32_t precision)
 
template<>
double round (double value, uint32_t precision)
 
template<>
long double round (long double value, uint32_t precision)
 
template<>
Fixed32 round (Fixed32 value, uint32_t precision)
 
template<>
Fixed64 round (Fixed64 value, uint32_t precision)
 
constexpr bool almost_zero (float value)
 Gets whether a given value is almost zero. More...
 
constexpr bool almost_zero (double value)
 Gets whether a given value is almost zero. More...
 
constexpr bool almost_zero (long double value)
 Gets whether a given value is almost zero. More...
 
constexpr bool almost_zero (Fixed32 value)
 Gets whether a given value is almost zero. More...
 
constexpr bool almost_equal (float x, float y, int ulp=2)
 
constexpr bool almost_equal (double x, double y, int ulp=2)
 
constexpr bool almost_equal (long double x, long double y, int ulp=2)
 
constexpr bool almost_equal (Fixed32 x, Fixed32 y, int ulp=2)
 
template<typename T >
Average (Span< const T > span)
 
template<>
Vec2 round (Vec2 value, std::uint32_t precision)
 
template<class T >
Angle GetAngle (T value)
 Gets the angle. More...
 
template<>
constexpr Vec3 GetInvalid () noexcept
 
template<typename T >
constexpr auto GetLengthSquared (T value) noexcept
 Gets the square of the length/magnitude of the given value. For performance, use this instead of GetLength(T value) (if possible). More...
 
template<>
constexpr auto GetLengthSquared (Vec3 value) noexcept
 
template<typename T >
auto GetLength (T value)
 
template<>
constexpr bool IsValid (const Vec3 &value) noexcept
 Does this vector contain finite coordinates? More...
 
template<typename T1 , typename T2 >
constexpr auto Dot (const T1 a, const T2 b) noexcept
 Performs the dot product on two vectors (A and B). More...
 
template<>
constexpr auto Dot (const Vec3 a, const Vec3 b) noexcept
 Perform the dot product on two vectors. More...
 
template<class T1 , class T2 >
constexpr auto Cross (const T1 a, const T2 b) noexcept
 Performs the 2D analog of the cross product of two vectors. More...
 
template<>
constexpr auto Cross (const Vec3 a, const Vec3 b) noexcept
 
template<>
constexpr bool IsValid (const Mat22 &value) noexcept
 
template<>
constexpr Mat22 GetInvalid () noexcept
 
constexpr Vec2 Solve (const Mat22 mat, const Vec2 b) noexcept
 Solve A * x = b, where b is a column vector. This is more efficient than computing the inverse in one-shot cases. More...
 
constexpr Mat22 Invert (const Mat22 value) noexcept
 
constexpr Vec3 Solve33 (const Mat33 &mat, const Vec3 b) noexcept
 Solve A * x = b, where b is a column vector. This is more efficient than computing the inverse in one-shot cases. More...
 
constexpr Vec2 Solve22 (const Mat33 &mat, const Vec2 b) noexcept
 Solve A * x = b, where b is a column vector. This is more efficient than computing the inverse in one-shot cases. Solve only the upper 2-by-2 matrix equation. More...
 
constexpr Mat33 GetInverse22 (const Mat33 &value) noexcept
 Get the inverse of this matrix as a 2-by-2. Returns the zero matrix if singular. More...
 
constexpr Mat33 GetSymInverse33 (const Mat33 &value) noexcept
 Get the symmetric inverse of this matrix as a 3-by-3. Returns the zero matrix if singular. More...
 
template<>
constexpr UnitVec2 GetInvalid () noexcept
 
template<>
constexpr bool IsValid (const UnitVec2 &value) noexcept
 
template<>
constexpr bool IsValid (const Transformation &value) noexcept
 
template<>
constexpr bool IsValid (const Position &value) noexcept
 
template<>
constexpr bool IsValid (const Velocity &value) noexcept
 
template<class T >
constexpr auto GetRevPerpendicular (const T vector) noexcept
 Gets a vector counter-clockwise (reverse-clockwise) perpendicular to the given vector. More...
 
template<class T >
constexpr auto GetFwdPerpendicular (const T vector) noexcept
 Gets a vector clockwise (forward-clockwise) perpendicular to the given vector. More...
 
constexpr Vec2 Transform (const Vec2 v, const Mat22 &A) noexcept
 Multiply a matrix times a vector. If a rotation matrix is provided, then this transforms the vector from one frame to another. More...
 
constexpr Vec2 InverseTransform (const Vec2 v, const Mat22 &A) noexcept
 Multiply a matrix transpose times a vector. If a rotation matrix is provided, then this transforms the vector from one frame to another (inverse transform). More...
 
constexpr Vec2 operator+ (const UnitVec2 lhs, const UnitVec2 rhs) noexcept
 
constexpr Vec2 operator- (const UnitVec2 lhs, const UnitVec2 rhs) noexcept
 
template<class T >
constexpr Vector2D< T > operator* (const T s, const UnitVec2 u) noexcept
 
template<class T >
constexpr Vector2D< T > operator* (const UnitVec2 u, const T s) noexcept
 
constexpr Vec2 operator/ (const UnitVec2 u, const UnitVec2::data_type s) noexcept
 
constexpr bool operator== (const Vec3 lhs, const Vec3 rhs) noexcept
 
constexpr bool operator!= (const Vec3 lhs, const Vec3 rhs) noexcept
 
constexpr bool operator== (Transformation lhs, Transformation rhs) noexcept
 
constexpr bool operator!= (Transformation lhs, Transformation rhs) noexcept
 
constexpr Vec3operator+= (Vec3 &lhs, const Vec3 &rhs) noexcept
 
constexpr Vec3operator-= (Vec3 &lhs, const Vec3 &rhs) noexcept
 
constexpr Vec3operator*= (Vec3 &lhs, const RealNum rhs) noexcept
 
constexpr Vec3 operator* (const RealNum s, const Vec3 a) noexcept
 
constexpr Vec3 operator+ (const Vec3 a, const Vec3 b) noexcept
 Add two vectors component-wise. More...
 
constexpr Vec3 operator- (const Vec3 a, const Vec3 b) noexcept
 Subtract two vectors component-wise. More...
 
constexpr Mat22 operator+ (const Mat22 A, const Mat22 B) noexcept
 
constexpr Mat22 Mul (const Mat22 &A, const Mat22 &B) noexcept
 
constexpr Mat22 MulT (const Mat22 &A, const Mat22 &B) noexcept
 
constexpr Vec3 Transform (const Vec3 &v, const Mat33 &A) noexcept
 Multiply a matrix times a vector. More...
 
constexpr Vec2 Transform (const Vec2 v, const Mat33 &A) noexcept
 Multiply a matrix times a vector. More...
 
template<class T >
constexpr auto Rotate (const Vector2D< T > vector, const UnitVec2 &angle) noexcept
 Rotates a vector by a given angle. More...
 
template<class T >
constexpr auto InverseRotate (const Vector2D< T > vector, const UnitVec2 &angle) noexcept
 Inverse rotate a vector. More...
 
constexpr Length2D Transform (const Length2D v, const Transformation T) noexcept
 Transforms the given 2-D vector with the given transformation. More...
 
constexpr Length2D InverseTransform (const Length2D v, const Transformation T) noexcept
 Inverse transforms the given 2-D vector with the given transformation. More...
 
constexpr Transformation Mul (const Transformation &A, const Transformation &B) noexcept
 
constexpr Transformation MulT (const Transformation &A, const Transformation &B) noexcept
 
template<>
Vec2 Abs (Vec2 a)
 
template<>
UnitVec2 Abs (UnitVec2 a)
 
Mat22 Abs (const Mat22 &A)
 
template<typename T >
constexpr T Min (T a, T b) noexcept
 
template<typename T >
constexpr T Max (T a, T b) noexcept
 
template<typename T >
constexpr T Clamp (T value, T low, T high) noexcept
 Clamps the given value within the given range (inclusive). More...
 
template<typename T >
constexpr void Swap (T &a, T &b)
 
std::uint64_t NextPowerOfTwo (std::uint64_t x)
 "Next Largest Power of 2 Given a binary integer value x, the next largest power of 2 can be computed by a SWAR algorithm that recursively "folds" the upper bits into the lower bits. This process yields a bit vector with the same most significant 1 as x, but all 1's below it. Adding 1 to that value yields the next largest power of 2. For a 64-bit value:" More...
 
constexpr bool operator== (const Position &lhs, const Position &rhs)
 
constexpr bool operator!= (const Position &lhs, const Position &rhs)
 
constexpr Position operator- (const Position &value)
 
constexpr Position operator+ (const Position &value)
 
constexpr Positionoperator+= (Position &lhs, const Position &rhs)
 
constexpr Position operator+ (const Position &lhs, const Position &rhs)
 
constexpr Positionoperator-= (Position &lhs, const Position &rhs)
 
constexpr Position operator- (const Position &lhs, const Position &rhs)
 
constexpr Position operator* (const Position &pos, const RealNum scalar)
 
constexpr Position operator* (const RealNum scalar, const Position &pos)
 
constexpr bool operator== (const Velocity &lhs, const Velocity &rhs)
 
constexpr bool operator!= (const Velocity &lhs, const Velocity &rhs)
 
constexpr Velocityoperator*= (Velocity &lhs, const RealNum rhs)
 
constexpr Velocityoperator/= (Velocity &lhs, const RealNum rhs)
 
constexpr Velocityoperator+= (Velocity &lhs, const Velocity &rhs)
 
constexpr Velocity operator+ (const Velocity &lhs, const Velocity &rhs)
 
constexpr Velocityoperator-= (Velocity &lhs, const Velocity &rhs)
 
constexpr Velocity operator- (const Velocity &lhs, const Velocity &rhs)
 
constexpr Velocity operator- (const Velocity &value)
 
constexpr Velocity operator+ (const Velocity &value)
 
constexpr Velocity operator* (const Velocity &lhs, const RealNum rhs)
 
constexpr Velocity operator* (const RealNum lhs, const Velocity &rhs)
 
constexpr Velocity operator/ (const Velocity &lhs, const RealNum rhs)
 
constexpr Transformation GetTransformation (const Length2D ctr, const UnitVec2 rot, const Length2D localCtr) noexcept
 
Transformation GetTransformation (const Position pos, const Length2D local_ctr) noexcept
 
Position GetPosition (const Position pos0, const Position pos1, const RealNum beta) noexcept
 Gets the position between two positions at a given unit interval. More...
 
Transformation GetTransformation (const Sweep &sweep, const RealNum beta) noexcept
 Gets the interpolated transform at a specific time. More...
 
Transformation GetTransform0 (const Sweep &sweep) noexcept
 Gets the transform at "time" zero. More...
 
Transformation GetTransform1 (const Sweep &sweep) noexcept
 Gets the transform at "time" one. More...
 
Angle GetNormalized (Angle value)
 
Sweep GetAnglesNormalized (Sweep sweep) noexcept
 Gets a sweep with the given sweep's angles normalized. More...
 
RealNum Normalize (Vec2 &vector)
 Converts the given vector into a unit vector and returns its original length. More...
 
bool IsUnderActive (Velocity velocity, LinearVelocity linSleepTol, AngularVelocity angSleepTol) noexcept
 
constexpr LinearVelocity2D GetContactRelVelocity (const Velocity velA, const Length2D vcp_rA, const Velocity velB, const Length2D vcp_rB) noexcept
 Gets the contact relative velocity. More...
 
template<>
Vec2 Average (Span< const Vec2 > span)
 
Length2D ComputeCentroid (const Span< const Length2D > &vertices)
 Computes the centroid of a counter-clockwise array of 3 or more vertices. More...
 
template<typename T >
constexpr T GetModuloNext (T value, T count) noexcept
 
template<typename T >
constexpr T GetModuloPrev (T value, T count) noexcept
 
constexpr Angle GetRevRotationalAngle (Angle a1, Angle a2) noexcept
 Gets the reverse (counter) clockwise rotational angle to go from angle 1 to angle 2. More...
 
constexpr Vec2 GetVec2 (const UnitVec2 value)
 
template<class T >
UnitVec2 GetUnitVector (const Vector2D< T > value, const UnitVec2 fallback=UnitVec2::GetDefaultFallback())
 Gets the unit vector for the given value. More...
 
template<class T >
UnitVec2 GetUnitVector (const Vector2D< T > value, T &magnitude, const UnitVec2 fallback=UnitVec2::GetDefaultFallback())
 Gets the unit vector for the given value. More...
 
template<>
UnitVec2 GetUnitVector (const Vector2D< RealNum > value, RealNum &magnitude, const UnitVec2 fallback)
 
::std::ostream & operator<< (::std::ostream &os, const Vec2 &value)
 
::std::ostream & operator<< (::std::ostream &os, const UnitVec2 &value)
 
::std::ostream & operator<< (::std::ostream &os, const Fixed32 &value)
 
void * alloc (size_t size)
 Implement this function to use your own memory allocator. More...
 
void * realloc (void *ptr, size_t new_size)
 Implement this function to use your own memory allocator. More...
 
void free (void *mem)
 If you implement alloc, you should also implement this function. More...
 
template<class... T>
void NOT_USED (T &&...)
 
constexpr RealNum StripUnit (const RealNum value)
 
template<typename T >
constexpr size_t max_list_size ()
 Maximum list size. More...
 
template<>
constexpr size_t max_list_size< Body > ()
 
template<>
constexpr size_t max_list_size< Contact > ()
 
template<>
constexpr size_t max_list_size< Joint > ()
 
template<typename T >
constexpr T GetInvalid () noexcept
 
template<>
constexpr float GetInvalid () noexcept
 
template<>
constexpr double GetInvalid () noexcept
 
template<>
constexpr long double GetInvalid () noexcept
 
template<>
constexpr Fixed32 GetInvalid () noexcept
 
template<>
constexpr Fixed64 GetInvalid () noexcept
 
template<>
constexpr size_t GetInvalid () noexcept
 
template<typename T >
constexpr bool IsValid (const T &value) noexcept
 
template<>
constexpr bool IsValid (const size_t &x) noexcept
 
template<typename T >
T * realloc (T *ptr, size_t size)
 
constexpr UnitVec2 GetXAxis (UnitVec2 rot) noexcept
 Get the x-axis. More...
 
constexpr UnitVec2 GetYAxis (UnitVec2 rot) noexcept
 Get the u-axis ("u"??? is that a typo??? Anyway, this is the reverse perpendicular vector of rot as a directional vector) More...
 
constexpr bool operator== (const UnitVec2 a, const UnitVec2 b) noexcept
 
constexpr bool operator!= (const UnitVec2 a, const UnitVec2 b) noexcept
 
constexpr UnitVec2 GetRevPerpendicular (const UnitVec2 vector) noexcept
 Gets a vector counter-clockwise (reverse-clockwise) perpendicular to the given vector. More...
 
constexpr UnitVec2 GetFwdPerpendicular (const UnitVec2 vector) noexcept
 Gets a vector clockwise (forward-clockwise) perpendicular to the given vector. More...
 
constexpr UnitVec2 Rotate (const UnitVec2 vector, const UnitVec2 &angle) noexcept
 Rotates a vector by a given angle. More...
 
constexpr UnitVec2 InverseRotate (const UnitVec2 vector, const UnitVec2 &angle) noexcept
 Inverse rotate a vector. More...
 
constexpr UnitVec2::data_type GetX (const UnitVec2 value)
 
constexpr UnitVec2::data_type GetY (const UnitVec2 value)
 
template<typename TYPE >
constexpr Vector2D< TYPE >::data_type GetX (const Vector2D< TYPE > value)
 
template<typename TYPE >
constexpr Vector2D< TYPE >::data_type GetY (const Vector2D< TYPE > value)
 
template<typename TYPE >
constexpr bool operator== (const Vector2D< TYPE > a, const Vector2D< TYPE > b) noexcept
 
template<typename TYPE >
constexpr bool operator!= (const Vector2D< TYPE > a, const Vector2D< TYPE > b) noexcept
 
template<typename TYPE >
constexpr Vector2D< TYPE > operator+ (const Vector2D< TYPE > a, const Vector2D< TYPE > b) noexcept
 Add two vectors component-wise. More...
 
template<typename TYPE >
constexpr Vector2D< TYPE > operator- (const Vector2D< TYPE > a, const Vector2D< TYPE > b) noexcept
 Subtract two vectors component-wise. More...
 
template<typename TYPE >
constexpr Vector2D< TYPE > & operator+= (Vector2D< TYPE > &lhs, const Vector2D< TYPE > rhs) noexcept
 Increment the left hand side value by the right hand side value. More...
 
template<typename TYPE >
constexpr Vector2D< TYPE > & operator-= (Vector2D< TYPE > &lhs, const Vector2D< TYPE > rhs) noexcept
 Decrement the left hand side value by the right hand side value. More...
 
template<typename TYPE >
constexpr Vector2D< TYPE > & operator*= (Vector2D< TYPE > &lhs, const RealNum rhs) noexcept
 
template<typename TYPE >
constexpr Vector2D< TYPE > & operator/= (Vector2D< TYPE > &lhs, const RealNum rhs) noexcept
 
template<typename TYPE1 , typename TYPE2 , typename OUT_TYPE = decltype(TYPE1{0} * TYPE2{0})>
constexpr Vector2D< OUT_TYPE > operator* (const TYPE1 s, const Vector2D< TYPE2 > a) noexcept
 
template<typename TYPE1 , typename TYPE2 , typename OUT_TYPE = decltype(TYPE1{0} * TYPE2{0})>
constexpr Vector2D< OUT_TYPE > operator* (const Vector2D< TYPE1 > a, const TYPE2 s) noexcept
 
template<typename TYPE1 , typename TYPE2 , typename OUT_TYPE = decltype(TYPE1{0} / TYPE2{0})>
constexpr Vector2D< OUT_TYPE > operator/ (const Vector2D< TYPE1 > a, const TYPE2 s) noexcept
 
constexpr Vec2 StripUnits (const Vector2D< RealNum > value)
 
template<>
constexpr Vec2 GetInvalid () noexcept
 
template<typename TYPE >
constexpr bool IsValid (const Vector2D< TYPE > &value) noexcept
 Does this vector contain finite coordinates? More...
 
const FixtureDefGetDefaultFixtureDef () noexcept
 
bool Awaken (Body &body) noexcept
 Awakens the body if it's asleep. More...
 
bool Unawaken (Body &body) noexcept
 Puts the body to sleep if it's awake. More...
 
bool ShouldCollide (const Body &lhs, const Body &rhs) noexcept
 Should collide. More...
 
void DestroyFixtures (Body &body)
 
Position GetPosition1 (const Body &body) noexcept
 
Mass GetMass (const Body &body) noexcept
 Gets the total mass of the body. More...
 
void ApplyLinearAcceleration (Body &body, const LinearAcceleration2D amount)
 
void SetForce (Body &body, const Force2D force, const Length2D point) noexcept
 
void ApplyForce (Body &body, const Force2D force, const Length2D point) noexcept
 Apply a force at a world point. More...
 
void ApplyForceToCenter (Body &body, const Force2D force) noexcept
 Apply a force to the center of mass. More...
 
void SetTorque (Body &body, const Torque torque) noexcept
 
void ApplyTorque (Body &body, const Torque torque) noexcept
 Apply a torque. More...
 
void ApplyLinearImpulse (Body &body, const Momentum2D impulse, const Length2D point) noexcept
 Apply an impulse at a point. More...
 
void ApplyAngularImpulse (Body &body, AngularMomentum impulse) noexcept
 Apply an angular impulse. More...
 
Force2D GetCentripetalForce (const Body &body, const Length2D axis)
 
RotInertia GetRotInertia (const Body &body) noexcept
 Gets the rotational inertia of the body. More...
 
RotInertia GetLocalInertia (const Body &body) noexcept
 Gets the rotational inertia of the body about the local origin. More...
 
MassData GetMassData (const Body &body) noexcept
 Gets the mass data of the body. More...
 
LinearVelocity2D GetLinearVelocity (const Body &body) noexcept
 Gets the linear velocity of the center of mass. More...
 
AngularVelocity GetAngularVelocity (const Body &body) noexcept
 Gets the angular velocity. More...
 
void SetLinearVelocity (Body &body, const LinearVelocity2D v) noexcept
 Sets the linear velocity of the center of mass. More...
 
void SetAngularVelocity (Body &body, AngularVelocity omega) noexcept
 Sets the angular velocity. More...
 
Length2D GetWorldPoint (const Body &body, const Length2D localPoint) noexcept
 Gets the world coordinates of a point given in coordinates relative to the body's origin. More...
 
Length2D GetWorldVector (const Body &body, const Length2D localVector) noexcept
 Gets the world coordinates of a vector given the local coordinates. More...
 
UnitVec2 GetWorldVector (const Body &body, const UnitVec2 localVector) noexcept
 
Length2D GetLocalPoint (const Body &body, const Length2D worldPoint) noexcept
 Gets a local point relative to the body's origin given a world point. More...
 
UnitVec2 GetLocalVector (const Body &body, const UnitVec2 uv) noexcept
 Gets a locally oriented unit vector given a world oriented unit vector. More...
 
LinearVelocity2D GetLinearVelocityFromWorldPoint (const Body &body, const Length2D worldPoint) noexcept
 Gets the linear velocity from a world point attached to this body. More...
 
LinearVelocity2D GetLinearVelocityFromLocalPoint (const Body &body, const Length2D localPoint) noexcept
 Gets the linear velocity from a local point. More...
 
Force2D GetForce (const Body &body) noexcept
 
Torque GetTorque (const Body &body) noexcept
 
Velocity GetVelocity (const Body &body, Time h) noexcept
 Gets the velocity of the body after the given time accounting for the body's acceleration. More...
 
size_t GetWorldIndex (const Body *body)
 
size_t GetFixtureCount (const Body &body)
 
void RotateAboutWorldPoint (Body &body, Angle amount, Length2D worldPoint)
 Rotates a body a given amount around a point in world coordinates. More...
 
void RotateAboutLocalPoint (Body &body, Angle amount, Length2D localPoint)
 Rotates a body a given amount around a point in body local coordinates. More...
 
BodyConstraint GetBodyConstraint (const Body &body, Time time=0) noexcept
 
RealNum MixFriction (RealNum friction1, RealNum friction2)
 Friction mixing law. The idea is to allow either fixture to drive the resulting friction to zero. For example, anything slides on ice. More...
 
RealNum MixRestitution (RealNum restitution1, RealNum restitution2) noexcept
 Restitution mixing law. The idea is allow for anything to bounce off an inelastic surface. For example, a superball bounces on anything. More...
 
bool HasSensor (const Contact &contact) noexcept
 
bool IsImpenetrable (const Contact &contact) noexcept
 
void SetAwake (Contact &c) noexcept
 
void ResetFriction (Contact &contact)
 Resets the friction mixture to the default value. More...
 
void ResetRestitution (Contact &contact) noexcept
 Reset the restitution to the default value. More...
 
TOIOutput CalcToi (const Contact &contact, const ToiConf conf)
 
PositionSolution operator+ (PositionSolution lhs, PositionSolution rhs)
 
PositionSolution operator- (PositionSolution lhs, PositionSolution rhs)
 
PositionSolution SolvePositionConstraint (const PositionConstraint &pc, const bool moveA, const bool moveB, ConstraintSolverConf conf)
 Solves the given position constraint. More...
 
ConstraintSolverConf GetDefaultPositionSolverConf ()
 
Length SolvePositionConstraints (Span< PositionConstraint > positionConstraints, ConstraintSolverConf conf=GetDefaultPositionSolverConf())
 Solves the given position constraints. More...
 
ConstraintSolverConf GetDefaultToiPositionSolverConf ()
 
Length SolvePositionConstraints (Span< PositionConstraint > positionConstraints, const BodyConstraint *bodiesA, const BodyConstraint *bodiesB, ConstraintSolverConf conf=GetDefaultToiPositionSolverConf())
 Solves the given position constraints. More...
 
Momentum SolveVelocityConstraint (VelocityConstraint &vc)
 Solves the velocity constraint. More...
 
PositionSolverManifold GetPSM (const Manifold &manifold, Manifold::size_type index, const Transformation &xfA, const Transformation &xfB)
 Gets the normal-point-separation data in world coordinates for the given inputs. More...
 
PositionSolverManifold GetPSM (const Manifold &manifold, Manifold::size_type index, Position pos_a, Length2D lc_ctr_a, Position pos_b, Length2D lc_ctr_b)
 Gets the normal-point-separation data in world coordinates for the given inputs. More...
 
UnitVec2 GetNormal (const VelocityConstraint &vc) noexcept
 Gets the normal of the velocity constraint contact in world coordinates. More...
 
UnitVec2 GetTangent (const VelocityConstraint &vc) noexcept
 
InvMass GetInvMass (const VelocityConstraint &vc) noexcept
 
Length2D GetPointRelPosA (const VelocityConstraint &vc, VelocityConstraint::size_type index)
 
Length2D GetPointRelPosB (const VelocityConstraint &vc, VelocityConstraint::size_type index)
 
LinearVelocity GetVelocityBiasAtPoint (const VelocityConstraint &vc, VelocityConstraint::size_type index)
 
Mass GetNormalMassAtPoint (const VelocityConstraint &vc, VelocityConstraint::size_type index)
 
Mass GetTangentMassAtPoint (const VelocityConstraint &vc, VelocityConstraint::size_type index)
 
Momentum GetNormalImpulseAtPoint (const VelocityConstraint &vc, VelocityConstraint::size_type index)
 
Momentum GetTangentImpulseAtPoint (const VelocityConstraint &vc, VelocityConstraint::size_type index)
 
Momentum2D GetNormalImpulses (const VelocityConstraint &vc)
 
Momentum2D GetTangentImpulses (const VelocityConstraint &vc)
 
void SetNormalImpulseAtPoint (VelocityConstraint &vc, VelocityConstraint::size_type index, Momentum value)
 
void SetTangentImpulseAtPoint (VelocityConstraint &vc, VelocityConstraint::size_type index, Momentum value)
 
void SetNormalImpulses (VelocityConstraint &vc, const Momentum2D impulses)
 
void SetTangentImpulses (VelocityConstraint &vc, const Momentum2D impulses)
 
bool TestPoint (const Fixture &f, const Length2D p) noexcept
 Test a point for containment in a fixture. More...
 
void SetAwake (Fixture &f) noexcept
 Sets the associated body's sleep status to awake. More...
 
Transformation GetTransformation (const Fixture &f) noexcept
 Gets the transformation associated with the given fixture. More...
 
bool IsFullOfBodies (const Island &island)
 
bool IsFullOfContacts (const Island &island)
 
std::size_t Count (const Island &island, const Body *entry)
 
std::size_t Count (const Island &island, const Contact *entry)
 
std::size_t Count (const Island &island, const Joint *entry)
 
bool IsEnabled (const Joint &j) noexcept
 Short-cut function to determine if both bodies are enabled. More...
 
void SetAwake (Joint &j) noexcept
 
size_t GetWorldIndex (const Joint *joint)
 
Length GetCurrentLengthA (const PulleyJoint &joint)
 Get the current length of the segment attached to bodyA. More...
 
Length GetCurrentLengthB (const PulleyJoint &joint)
 Get the current length of the segment attached to bodyB. More...
 
Angle GetJointAngle (const RevoluteJoint &joint)
 Get the current joint angle in radians. More...
 
AngularVelocity GetJointSpeed (const RevoluteJoint &joint)
 Get the current joint angle speed in radians per second. More...
 
Length GetMaxRegLinearCorrection (const StepConf &conf) noexcept
 
bool IsMaxTranslationWithinTolerance (const StepConf &conf) noexcept
 
StepStats Step (World &world, Time timeStep, World::ts_iters_type velocityIterations=8, World::ts_iters_type positionIterations=3)
 Steps the world ahead by a given time amount. More...
 
size_t GetFixtureCount (const World &world) noexcept
 Gets the count of fixtures in the given world. More...
 
size_t GetShapeCount (const World &world) noexcept
 Gets the count of unique shapes in the given world. More...
 
size_t GetAwakeCount (const World &world) noexcept
 Gets the count of awake bodies in the given world. More...
 
size_t Awaken (World &world)
 Awakens all of the bodies in the given world. More...
 
void ClearForces (World &world) noexcept
 Clears forces. More...
 
bool IsActive (const Contact &contact) noexcept
 
World::Bodies::size_type GetBodyCount (const World &world) noexcept
 Gets the body count in the given world. More...
 
joint_count_t GetJointCount (const World &world) noexcept
 Gets the count of joints in the given world. More...
 
World::Contacts::size_type GetContactCount (const World &world) noexcept
 Gets the count of contacts in the given world. More...
 

Variables

constexpr auto Vec2_zero = Vec2{0, 0}
 An all zero Vec2 value. More...
 
constexpr auto Vec3_zero = Vec3{0, 0, 0}
 An all zero Vec3 value. More...
 
constexpr auto Mat22_zero = Mat22(Vec2_zero, Vec2_zero)
 An all zero Mat22 value. More...
 
constexpr auto Mat22_identity = Mat22(Vec2{1, 0}, Vec2{0, 1})
 Identity value for Mat22 objects. More...
 
constexpr auto Mat33_zero = Mat33(Vec3_zero, Vec3_zero, Vec3_zero)
 
constexpr auto Transform_identity = Transformation{Vec2_zero * Meter, UnitVec2::GetRight()}
 
constexpr auto Pi = RealNum(3.14159265358979323846264338327950288)
 Pi. More...
 
constexpr auto Second = RealNum{1}
 
constexpr auto Hertz = RealNum{1}
 
constexpr auto Meter = RealNum{1}
 
constexpr auto MeterPerSecond = RealNum{1}
 
constexpr auto MeterPerSquareSecond = RealNum{1}
 
constexpr auto Kilogram = RealNum{1}
 
constexpr auto SquareMeter = RealNum{1}
 
constexpr auto KilogramPerSquareMeter = RealNum{1}
 
constexpr auto Radian = RealNum{1}
 
constexpr auto Degree = Pi / RealNum{180}
 
constexpr auto SquareRadian = Radian * Radian
 
constexpr auto RadianPerSecond = RealNum{1}
 
constexpr auto RadianPerSquareSecond = RealNum{1}
 
constexpr auto Newton = RealNum{1}
 
constexpr auto NewtonMeter = RealNum{1}
 
constexpr auto NewtonSecond = RealNum{1}
 
constexpr auto MaxFloat = std::numeric_limits<RealNum>::max()
 
constexpr auto MaxManifoldPoints = std::uint8_t{2}
 Maximum manifold points. This is the maximum number of contact points between two convex shapes. Do not change this value. More...
 
constexpr auto MaxShapeVertices = std::uint8_t{254}
 Maximum number of vertices for any shape type. More...
 
constexpr auto DefaultLinearSlop = Length{Meter / RealNum{1000}}
 Default linear slop. More...
 
constexpr auto DefaultAabbExtension = DefaultLinearSlop * RealNum{20}
 
constexpr auto DefaultDistanceMultiplier = RealNum{2}
 
constexpr auto DefaultAngularSlop = (Pi * RealNum{2} * Radian) / RealNum{180}
 Default angular slop. More...
 
constexpr auto DefaultMaxLinearCorrection = DefaultLinearSlop * RealNum{40}
 Default maximum linear correction. More...
 
constexpr auto DefaultMaxAngularCorrection = DefaultAngularSlop * RealNum{4}
 Default maximum angular correction. More...
 
constexpr auto DefaultMaxToiIters = std::uint8_t{20}
 Default maximum time of impact iterations. More...
 
constexpr auto DefaultMaxToiRootIters = std::uint8_t{30}
 Default maximum time of impact root iterator count. More...
 
constexpr auto DefaultMaxDistanceIters = std::uint8_t{20}
 Default max number of distance iterations. More...
 
constexpr auto DefaultMaxSubSteps = std::uint8_t{48}
 Default maximum number of sub steps. More...
 
constexpr auto DefaultVelocityThreshold = (RealNum{8} / RealNum{10}) * MeterPerSecond
 Default velocity threshold. More...
 
constexpr auto MaxBodies
 Maximum number of bodies in a world (65534 based off uint16_t and eliminating one value for invalid). More...
 
constexpr auto MaxContacts = contact_count_t{MaxBodies} * contact_count_t{MaxBodies - 1} / contact_count_t{2}
 Maximum number of contacts in a world (2147319811). More...
 
constexpr auto MaxJoints
 Maximum number of joints in a world (65534 based off std::uint16_t and eliminating one value for invalid). More...
 
constexpr auto DefaultStepTime = Time{Second / RealNum{60}}
 
constexpr auto DefaultStepFrequency = Frequency{Hertz * RealNum{60}}
 
constexpr auto DefaultMinStillTimeToSleep = Time{Second / RealNum{2}}
 Default minimum still time to sleep. More...
 
constexpr auto DefaultLinearSleepTolerance = RealNum{0.01f} * MeterPerSecond
 Default linear sleep tolerance. More...
 
constexpr auto DefaultAngularSleepTolerance = RealNum{(Pi * 2) / 180} * RadianPerSecond
 Default angular sleep tolerance. More...
 
constexpr auto BuiltVersion = Version{3, 0, 0}
 
constexpr auto EarthlyGravity = LinearAcceleration2D{RealNum{0} * MeterPerSquareSecond, RealNum{-9.8f} * MeterPerSquareSecond}
 Earthly gravity. More...
 

Detailed Description

Namespace for all Box2D related names.

Typedef Documentation

◆ Angle

using box2d::Angle = typedef RealNum

◆ AngularAcceleration

◆ AngularMomentum

◆ AngularVelocity

◆ Area

using box2d::Area = typedef RealNum

◆ body_count_t

using box2d::body_count_t = typedef std::remove_const<decltype(MaxBodies)>::type

Body count type.

◆ BodyConstraints

typedef std::unordered_map< const Body *, BodyConstraint > box2d::BodyConstraints

◆ child_count_t

using box2d::child_count_t = typedef unsigned

Child count type.

Relating to "children" of Shape.

◆ ClipList

Clip list for ClipSegmentToLine.

See also
ClipSegmentToLine.
Note
This data structure is at least 24-bytes large.

◆ contact_count_t

using box2d::contact_count_t = typedef Wider<body_count_t>::type

Contact count type.

◆ Density

using box2d::Density = typedef RealNum

◆ Fixed32

using box2d::Fixed32 = typedef Fixed<std::int32_t,14>

◆ Fixed64

using box2d::Fixed64 = typedef Fixed<std::int64_t,24>

◆ Force

using box2d::Force = typedef RealNum

◆ Force2D

using box2d::Force2D = typedef Vector2D<Force>

◆ Frequency

using box2d::Frequency = typedef RealNum

◆ InvMass

using box2d::InvMass = typedef RealNum

◆ InvRotInertia

using box2d::InvRotInertia = typedef RealNum

◆ island_count_t

using box2d::island_count_t = typedef size_t

Island count type.

Relating to items in a Island.

◆ joint_count_t

using box2d::joint_count_t = typedef std::remove_const<decltype(MaxJoints)>::type

Joint count type.

◆ Length

using box2d::Length = typedef RealNum

◆ Length2D

using box2d::Length2D = typedef Vector2D<Length>

◆ LinearAcceleration

◆ LinearAcceleration2D

◆ LinearVelocity

using box2d::LinearVelocity = typedef RealNum

◆ LinearVelocity2D

◆ Mass

using box2d::Mass = typedef RealNum

◆ Momentum

using box2d::Momentum = typedef RealNum

◆ Momentum2D

◆ PointStateArray

◆ PositionConstraints

using box2d::PositionConstraints = typedef std::vector<PositionConstraint>

◆ RealNum

using box2d::RealNum = typedef float

Real-number type.

This is the number type underlying numerical calculations conceptually involving real-numbers. Ideally the implementation of this type doesn't suffer from things like: catastrophic cancellation, catastrophic division, overflows, nor underflows.

Note
This can be implemented using float, double, long double, Fixed32, or Fixed64.
Regarding division:

While dividing 1 by a RealNum, caching the result, and then doing multiplications with the result may well be faster (than repeatedly dividing), dividing 1 by RealNum can also result in an underflow situation that's then compounded every time it's multiplied with other values.

Meanwhile, dividing every value by RealNum isolates any underflows to the particular division where underflow occurs.

Warning
The note regarding division applies even more so when using a fixed-point type (for RealNum).

◆ RotInertia

using box2d::RotInertia = typedef RealNum

◆ SecondMomentOfArea

◆ size_t

using box2d::size_t = typedef std::size_t

Size type for sizing data.

◆ Time

using box2d::Time = typedef RealNum

◆ Torque

using box2d::Torque = typedef RealNum

◆ ts_iters_t

using box2d::ts_iters_t = typedef std::uint8_t

Time step iterations type.

A type for countining iterations per time-step.

◆ Vec2

using box2d::Vec2 = typedef Vector2D<RealNum>

Vector 2D of RealNum.

Note
This data structure is two-times the size of the RealNum type (or 8 using RealNum of float).

◆ VelocityConstraints

using box2d::VelocityConstraints = typedef std::vector<VelocityConstraint>

Enumeration Type Documentation

◆ BodyType

enum box2d::BodyType
strong

Body Type.

Note
static: zero mass, zero velocity, may be manually moved
kinematic: zero mass, non-zero velocity set by user, moved by solver
dynamic: positive mass, non-zero velocity determined by forces, moved by solver
Enumerator
Static 

Static body type.

Static bodies have no mass, have no forces applied to them, and aren't moved by physical processeses. They are impenetrable.

Note
Physics applied: none.
Kinematic 

Kinematic body type.

Kinematic bodies have no mass and have no forces applied to them, but can move at set velocities. They are impenetrable.

Note
Physics applied: velocity.
Dynamic 

Dynamic body type.

Dynamic bodies are fully simulated bodies. Dynamic bodies always have a positive non-zero mass. They may be penetrable.

Note
Physics applied: velocity, acceleration.

◆ JointType

enum box2d::JointType
strong
Enumerator
Unknown 
Revolute 
Prismatic 
Distance 
Pulley 
Mouse 
Gear 
Wheel 
Weld 
Friction 
Rope 
Motor 

◆ PointState

enum box2d::PointState
strong

This is used for determining the state of contact points.

Enumerator
NullState 

point does not exist

AddState 

point was added in the update

PersistState 

point persisted across the update

RemoveState 

point was removed in the update

Function Documentation

◆ Abs() [1/4]

template<typename T >
constexpr T box2d::Abs ( a)
inline

◆ Abs() [2/4]

template<>
Vec2 box2d::Abs ( Vec2  a)
inline

◆ Abs() [3/4]

template<>
UnitVec2 box2d::Abs ( UnitVec2  a)
inline

◆ Abs() [4/4]

Mat22 box2d::Abs ( const Mat22 A)
inline

◆ alloc()

T * box2d::alloc ( size_t  size)

Implement this function to use your own memory allocator.

◆ almost_equal() [1/4]

constexpr bool box2d::almost_equal ( float  x,
float  y,
int  ulp = 2 
)
inline

◆ almost_equal() [2/4]

constexpr bool box2d::almost_equal ( double  x,
double  y,
int  ulp = 2 
)
inline

◆ almost_equal() [3/4]

constexpr bool box2d::almost_equal ( long double  x,
long double  y,
int  ulp = 2 
)
inline

◆ almost_equal() [4/4]

constexpr bool box2d::almost_equal ( Fixed32  x,
Fixed32  y,
int  ulp = 2 
)
inline

◆ almost_zero() [1/4]

constexpr bool box2d::almost_zero ( float  value)
inline

Gets whether a given value is almost zero.

An almost zero value is "subnormal". Dividing by these values can lead to odd results like a divide by zero trap occuring.

Returns
true if the given value is almost zero, false otherwise.

◆ almost_zero() [2/4]

constexpr bool box2d::almost_zero ( double  value)
inline

Gets whether a given value is almost zero.

An almost zero value is "subnormal". Dividing by these values can lead to odd results like a divide by zero trap occuring.

Returns
true if the given value is almost zero, false otherwise.

◆ almost_zero() [3/4]

constexpr bool box2d::almost_zero ( long double  value)
inline

Gets whether a given value is almost zero.

An almost zero value is "subnormal". Dividing by these values can lead to odd results like a divide by zero trap occuring.

Returns
true if the given value is almost zero, false otherwise.

◆ almost_zero() [4/4]

constexpr bool box2d::almost_zero ( Fixed32  value)
inline

Gets whether a given value is almost zero.

An almost zero value is "subnormal". Dividing by these values can lead to odd results like a divide by zero trap occuring.

Returns
true if the given value is almost zero, false otherwise.

◆ ApplyAngularImpulse()

void box2d::ApplyAngularImpulse ( Body body,
AngularMomentum  impulse 
)
inlinenoexcept

Apply an angular impulse.

Parameters
bodyBody to apply the angular impulse to.
impulsethe angular impulse in units of kg*m*m/s

◆ ApplyForce()

void box2d::ApplyForce ( Body body,
const Force2D  force,
const Length2D  point 
)
inlinenoexcept

Apply a force at a world point.

Note
If the force is not applied at the center of mass, it will generate a torque and affect the angular velocity.
Non-zero forces wakes up the body.
Parameters
bodyBody to apply the force to.
forceWorld force vector, usually in Newtons (N).
pointWorld position of the point of application.

◆ ApplyForceToCenter()

void box2d::ApplyForceToCenter ( Body body,
const Force2D  force 
)
inlinenoexcept

Apply a force to the center of mass.

Note
Non-zero forces wakes up the body.
Parameters
bodyBody to apply the force to.
forceWorld force vector, usually in Newtons (N).

◆ ApplyLinearAcceleration()

void box2d::ApplyLinearAcceleration ( Body body,
const LinearAcceleration2D  amount 
)
inline

◆ ApplyLinearImpulse()

void box2d::ApplyLinearImpulse ( Body body,
const Momentum2D  impulse,
const Length2D  point 
)
inlinenoexcept

Apply an impulse at a point.

Note
This immediately modifies the velocity.
This also modifies the angular velocity if the point of application is not at the center of mass.
Non-zero impulses wakes up the body.
Parameters
bodyBody to apply the impulse to.
impulsethe world impulse vector, usually in N-seconds or kg-m/s.
pointthe world position of the point of application.

◆ ApplyTorque()

void box2d::ApplyTorque ( Body body,
const Torque  torque 
)
inlinenoexcept

Apply a torque.

Note
This affects the angular velocity without affecting the linear velocity of the center of mass.
Non-zero forces wakes up the body.
Parameters
bodyBody to apply the torque to.
torqueabout the z-axis (out of the screen), usually in N-m.

◆ Atan2()

template<typename T >
auto box2d::Atan2 ( y,
x 
)
inline

◆ Average() [1/2]

template<typename T >
T box2d::Average ( Span< const T >  span)
inline

◆ Average() [2/2]

template<>
Vec2 box2d::Average ( Span< const Vec2 span)
inline

◆ Awaken() [1/2]

bool box2d::Awaken ( Body body)
inlinenoexcept

Awakens the body if it's asleep.

◆ Awaken() [2/2]

size_t box2d::Awaken ( World world)

Awakens all of the bodies in the given world.

Calls all of the world's bodies' SetAwake method.

Returns
Sum total of calls to bodies' SetAwake method that returned true.
See also
Body::SetAwake.

◆ CalcToi()

TOIOutput box2d::CalcToi ( const Contact contact,
const ToiConf  conf 
)

◆ Clamp()

template<typename T >
constexpr T box2d::Clamp ( value,
low,
high 
)
inlinenoexcept

Clamps the given value within the given range (inclusive).

Parameters
valueValue to clamp.
lowLowest value to return or NaN to keep the low-end unbounded.
highHighest value to return or NaN to keep the high-end unbounded.

◆ ClearForces()

void box2d::ClearForces ( World world)
noexcept

Clears forces.

Manually clear the force buffer on all bodies.

◆ ClipSegmentToLine()

ClipList box2d::ClipSegmentToLine ( const ClipList vIn,
const UnitVec2 normal,
Length  offset,
ContactFeature::index_t  indexA 
)

Clipping for contact manifolds.

This returns an array of points from the given line that are inside of the plane as defined by a given normal and offset.

Parameters
vInClip list of two points defining the line.
normalNormal of the plane with which to determine intersection.
offsetOffset of the plane with which to determine intersection.
indexAIndex of vertex A.
Returns
List of zero one or two clip points.

◆ CollideShapes()

Manifold box2d::CollideShapes ( const DistanceProxy shapeA,
const Transformation xfA,
const DistanceProxy shapeB,
const Transformation xfB,
const Manifold::Conf  conf = GetDefaultManifoldConf() 
)

◆ ComputeAABB() [1/3]

AABB box2d::ComputeAABB ( const DistanceProxy proxy,
const Transformation  xf 
)

Given a transform, compute the associated axis aligned bounding box for a child shape.

Parameters
proxyDistance proxy for the child shape.
xfWorld transform of the shape.
Returns
the axis aligned box.

◆ ComputeAABB() [2/3]

AABB box2d::ComputeAABB ( const Shape shape,
const Transformation  xf 
)

◆ ComputeAABB() [3/3]

AABB box2d::ComputeAABB ( const Body body)

◆ ComputeCentroid()

Length2D box2d::ComputeCentroid ( const Span< const Length2D > &  vertices)

Computes the centroid of a counter-clockwise array of 3 or more vertices.

Note
Behavior is undefined if there are less than 3 vertices or the vertices don't go counter-clockwise.

◆ ComputeMassData()

MassData box2d::ComputeMassData ( const Body body)
noexcept

Computes the body's mass data.

This basically accumulates the mass data over all fixtures.

Note
The center is the mass weighted sum of all fixture centers. Divide it by the mass to get the averaged center.
Returns
accumalated mass data for all fixtures associated with the given body.

◆ Count() [1/3]

std::size_t box2d::Count ( const Island island,
const Body entry 
)

◆ Count() [2/3]

std::size_t box2d::Count ( const Island island,
const Contact entry 
)

◆ Count() [3/3]

std::size_t box2d::Count ( const Island island,
const Joint entry 
)

◆ Cross() [1/2]

template<class T1 , class T2 >
constexpr auto box2d::Cross ( const T1  a,
const T2  b 
)
inlinenoexcept

Performs the 2D analog of the cross product of two vectors.

This is defined as the result of: (a.x * b.y) - (a.y * b.x).

Note
This operation is anti-commutative. I.e. Cross(a, b) == -Cross(b, a).
The result will be 0 if any of the following are true: vector A or vector B has a length of zero; vectors A and B point in the same direction; or vectors A and B point in exactly opposite direction of each other.
The result will be positive if: neither vector A nor B has a length of zero; and vector B is at an angle from vector A of greater than 0 and less than 180 degrees (counter-clockwise from A being a positive angle).
Result will be negative if: neither vector A nor B has a length of zero; and vector B is at an angle from vector A of less than 0 and greater than -180 degrees (clockwise from A being a negative angle).
The absolute value of the result is the area of the parallelogram formed by the vectors A and B.
See also
https://en.wikipedia.org/wiki/Cross_product
Parameters
aVector A.
bVector B.
Returns
Cross product of the two vectors.

◆ Cross() [2/2]

template<>
constexpr auto box2d::Cross ( const Vec3  a,
const Vec3  b 
)
inlinenoexcept

◆ Delete()

template<typename T >
void box2d::Delete ( const T *  p,
BlockAllocator allocator 
)
inline

◆ DestroyFixtures()

void box2d::DestroyFixtures ( Body body)

◆ Distance()

DistanceOutput box2d::Distance ( const DistanceProxy proxyA,
const Transformation transformA,
const DistanceProxy proxyB,
const Transformation transformB,
const DistanceConf  conf = DistanceConf{} 
)

Determines the closest points between two shapes.

Supports any combination of: CircleShape, PolygonShape, EdgeShape. The simplex cache is input/output.

Note
On the first call, the Simplex::Cache.count should be set to zero.
Parameters
proxyAProxy A.
transformATransoform of A.
proxyBProxy B.
transformBTransoform of B.
confConfiguration to use including the simplex cache for assisting the determination.
Returns
Closest points between the two shapes and the count of iterations it took to determine them. The iteration count will always be greater than zero unless DefaultMaxDistanceIters is zero.

◆ Dot() [1/2]

template<typename T1 , typename T2 >
constexpr auto box2d::Dot ( const T1  a,
const T2  b 
)
inlinenoexcept

Performs the dot product on two vectors (A and B).

The dot product of two vectors is defined as: the magnitude of vector A, mulitiplied by, the magnitude of vector B, multiplied by, the cosine of the angle between the two vectors (A and B). Thus the dot product of two vectors is a value ranging between plus and minus the magnitudes of each vector times each other. The middle value of 0 indicates that two vectors are perpendicular to each other (at an angle of +/- 90 degrees from each other).

Note
This operation is commutative. I.e. Dot(a, b) == Dot(b, a).
If A and B are the same vectors, GetLengthSquared(Vec2) returns the same value using effectively one less input parameter.
See also
https://en.wikipedia.org/wiki/Dot_product
Parameters
aVector A.
bVector B.
Returns
Dot product of the vectors (0 means the two vectors are perpendicular).

◆ Dot() [2/2]

template<>
constexpr auto box2d::Dot ( const Vec3  a,
const Vec3  b 
)
inlinenoexcept

Perform the dot product on two vectors.

◆ Dump() [1/15]

void box2d::Dump ( const World world)

Dump the world into the log file.

Warning
this should be called outside of a time step.

◆ Dump() [2/15]

void box2d::Dump ( const Body body,
size_t  bodyIndex 
)

Dump body to a log file.

◆ Dump() [3/15]

void box2d::Dump ( const Joint joint,
size_t  index 
)

Dump joint to the log file.

◆ Dump() [4/15]

void box2d::Dump ( const Fixture fixture,
size_t  bodyIndex 
)

Dump fixture to log file.

◆ Dump() [5/15]

void box2d::Dump ( const DistanceJoint joint,
size_t  index 
)

Dump joint to dmLog.

◆ Dump() [6/15]

void box2d::Dump ( const FrictionJoint joint,
size_t  index 
)

Dump joint to the log file.

◆ Dump() [7/15]

void box2d::Dump ( const GearJoint joint,
size_t  index 
)

◆ Dump() [8/15]

void box2d::Dump ( const MotorJoint joint,
size_t  index 
)

◆ Dump() [9/15]

void box2d::Dump ( const MouseJoint joint,
size_t  index 
)

◆ Dump() [10/15]

void box2d::Dump ( const PrismaticJoint joint,
size_t  index 
)

◆ Dump() [11/15]

void box2d::Dump ( const PulleyJoint joint,
size_t  index 
)

Dump joint to dmLog.

◆ Dump() [12/15]

void box2d::Dump ( const RevoluteJoint joint,
size_t  index 
)

◆ Dump() [13/15]

void box2d::Dump ( const RopeJoint joint,
size_t  index 
)

◆ Dump() [14/15]

void box2d::Dump ( const WeldJoint joint,
size_t  index 
)

◆ Dump() [15/15]

void box2d::Dump ( const WheelJoint joint,
size_t  index 
)

◆ FindLowestRightMostVertex()

size_t box2d::FindLowestRightMostVertex ( Span< const Length2D vertices)

◆ Flip()

constexpr ContactFeature box2d::Flip ( ContactFeature  val)
noexcept

Flips contact features information.

◆ free()

void box2d::free ( void *  mem)

If you implement alloc, you should also implement this function.

◆ GetAABB()

AABB box2d::GetAABB ( const Fixture fixture,
child_count_t  childIndex 
)
noexcept

Gets the fixture's AABB.

Note
This AABB may be enlarged and/or stale. If you need a more accurate AABB, compute it using the shape and the body transform.
Warning
Behavior is undefined is child index is not a valid proxy index.
See also
Fixture::GetProxy.

◆ GetAngle()

template<class T >
Angle box2d::GetAngle ( value)
inline

Gets the angle.

Returns
Anglular value in the range of -Pi to +Pi radians.

◆ GetAnglesNormalized()

Sweep box2d::GetAnglesNormalized ( Sweep  sweep)
inlinenoexcept

Gets a sweep with the given sweep's angles normalized.

Parameters
sweepSweep to return with its angles normalized.
Returns
Sweep with its pos0 angle in radians to be between -2 pi and 2 pi and its pos1 angle reduced by the amount pos0's angle was reduced by.

◆ GetAngularVelocity()

AngularVelocity box2d::GetAngularVelocity ( const Body body)
inlinenoexcept

Gets the angular velocity.

Parameters
bodyBody to get the angular velocity for.
Returns
the angular velocity in radians/second.

◆ GetAreaOfCircle()

Area box2d::GetAreaOfCircle ( Length  radius)

◆ GetAreaOfPolygon()

Area box2d::GetAreaOfPolygon ( Span< const Length2D vertices)

◆ GetAwakeCount()

size_t box2d::GetAwakeCount ( const World world)
noexcept

Gets the count of awake bodies in the given world.

◆ GetBodyConstraint()

box2d::BodyConstraint box2d::GetBodyConstraint ( const Body body,
Time  time = 0 
)
noexcept

◆ GetBodyCount()

World::Bodies::size_type box2d::GetBodyCount ( const World world)
inlinenoexcept

Gets the body count in the given world.

Returns
0 or higher.

◆ GetCenter()

constexpr Length2D box2d::GetCenter ( const AABB  aabb)
noexcept

Gets the center of the AABB.

◆ GetCentripetalForce()

Force2D box2d::GetCentripetalForce ( const Body body,
const Length2D  axis 
)

◆ GetClosestPoint()

BOX2D_CONSTEXPR Length2D box2d::GetClosestPoint ( const Simplex simplex)
inline

Gets the "closest point".

◆ GetContactCount()

World::Contacts::size_type box2d::GetContactCount ( const World world)
inlinenoexcept

Gets the count of contacts in the given world.

Note
Not all contacts are for shapes that are actually touching. Some contacts are for shapes which merely have overlapping AABBs.
Returns
0 or higher.

◆ GetContactRelVelocity()

constexpr LinearVelocity2D box2d::GetContactRelVelocity ( const Velocity  velA,
const Length2D  vcp_rA,
const Velocity  velB,
const Length2D  vcp_rB 
)
inlinenoexcept

Gets the contact relative velocity.

Note
If vcp_rA and vcp_rB are the zero vectors, the resulting value is simply velB.linear - velA.linear.

◆ GetConvexHullAsVector()

std::vector< Length2D > box2d::GetConvexHullAsVector ( Span< const Length2D vertices)

◆ GetCurrentLengthA()

Length box2d::GetCurrentLengthA ( const PulleyJoint joint)

Get the current length of the segment attached to bodyA.

◆ GetCurrentLengthB()

Length box2d::GetCurrentLengthB ( const PulleyJoint joint)

Get the current length of the segment attached to bodyB.

◆ GetDefaultFixtureDef()

const FixtureDef & box2d::GetDefaultFixtureDef ( )
noexcept

◆ GetDefaultManifoldConf()

constexpr Manifold::Conf box2d::GetDefaultManifoldConf ( )
inlinenoexcept

◆ GetDefaultPositionSolverConf()

ConstraintSolverConf box2d::GetDefaultPositionSolverConf ( )
inline

◆ GetDefaultToiConf()

constexpr auto box2d::GetDefaultToiConf ( )

◆ GetDefaultToiPositionSolverConf()

ConstraintSolverConf box2d::GetDefaultToiPositionSolverConf ( )
inline

◆ GetDimensions()

constexpr Length2D box2d::GetDimensions ( const AABB  aabb)
noexcept

◆ GetDisplacedAABB()

constexpr AABB box2d::GetDisplacedAABB ( AABB  aabb,
const Length2D  displacement 
)

◆ GetDistanceProxy()

DistanceProxy box2d::GetDistanceProxy ( const Shape shape,
child_count_t  index 
)

Initialize the proxy using the given shape.

Note
The shape must remain in scope while the proxy is in use.

◆ GetEdge()

Length2D box2d::GetEdge ( const PolygonShape shape,
PolygonShape::vertex_count_t  index 
)

Gets the identified edge of the given polygon shape.

Note
This must not be called for shapes with less than 2 vertices.
Warning
Behavior is undefined if called for a shape with less than 2 vertices.

◆ GetEnclosingAABB()

constexpr AABB box2d::GetEnclosingAABB ( AABB  a,
AABB  b 
)

◆ GetExtents()

constexpr Length2D box2d::GetExtents ( const AABB  aabb)
noexcept

Gets the extents of the AABB (half-widths).

◆ GetFaceFaceContactFeature()

constexpr ContactFeature box2d::GetFaceFaceContactFeature ( ContactFeature::index_t  a,
ContactFeature::index_t  b 
)
noexcept

◆ GetFaceVertexContactFeature()

constexpr ContactFeature box2d::GetFaceVertexContactFeature ( ContactFeature::index_t  a,
ContactFeature::index_t  b 
)
noexcept

◆ GetFattenedAABB()

constexpr AABB box2d::GetFattenedAABB ( AABB  aabb,
const Length  amount 
)

◆ GetFixtureCount() [1/2]

size_t box2d::GetFixtureCount ( const Body body)

◆ GetFixtureCount() [2/2]

size_t box2d::GetFixtureCount ( const World world)
noexcept

Gets the count of fixtures in the given world.

◆ GetForce()

Force2D box2d::GetForce ( const Body body)
inlinenoexcept

◆ GetFwdPerpendicular() [1/2]

constexpr UnitVec2 box2d::GetFwdPerpendicular ( const UnitVec2  vector)
inlinenoexcept

Gets a vector clockwise (forward-clockwise) perpendicular to the given vector.

This takes a vector of form (x, y) and returns the vector (y, -x).

Parameters
vectorVector to return a clockwise perpendicular equivalent for.
Returns
A clockwise 90-degree rotation of the given vector.
See also
GetRevPerpendicular.

◆ GetFwdPerpendicular() [2/2]

template<class T >
constexpr auto box2d::GetFwdPerpendicular ( const T  vector)
inlinenoexcept

Gets a vector clockwise (forward-clockwise) perpendicular to the given vector.

This takes a vector of form (x, y) and returns the vector (y, -x).

Parameters
vectorVector to return a clockwise perpendicular equivalent for.
Returns
A clockwise 90-degree rotation of the given vector.
See also
GetRevPerpendicular.

◆ GetInvalid() [1/12]

template<>
constexpr AABB box2d::GetInvalid ( )
inlinenoexcept

◆ GetInvalid() [2/12]

template<>
constexpr Vec2 box2d::GetInvalid ( )
inlinenoexcept

◆ GetInvalid() [3/12]

template<>
constexpr Vec3 box2d::GetInvalid ( )
inlinenoexcept

◆ GetInvalid() [4/12]

template<>
constexpr Mat22 box2d::GetInvalid ( )
inlinenoexcept

◆ GetInvalid() [5/12]

template<typename T >
constexpr T box2d::GetInvalid ( )
inlinenoexcept

◆ GetInvalid() [6/12]

template<>
constexpr float box2d::GetInvalid ( )
inlinenoexcept

◆ GetInvalid() [7/12]

template<>
constexpr double box2d::GetInvalid ( )
inlinenoexcept

◆ GetInvalid() [8/12]

template<>
constexpr long double box2d::GetInvalid ( )
inlinenoexcept

◆ GetInvalid() [9/12]

template<>
constexpr Fixed32 box2d::GetInvalid ( )
inlinenoexcept

◆ GetInvalid() [10/12]

template<>
constexpr Fixed64 box2d::GetInvalid ( )
inlinenoexcept

◆ GetInvalid() [11/12]

template<>
constexpr size_t box2d::GetInvalid ( )
inlinenoexcept

◆ GetInvalid() [12/12]

template<>
constexpr UnitVec2 box2d::GetInvalid ( )
inlinenoexcept

◆ GetInverse22()

constexpr Mat33 box2d::GetInverse22 ( const Mat33 value)
inlinenoexcept

Get the inverse of this matrix as a 2-by-2. Returns the zero matrix if singular.

◆ GetInvMass()

InvMass box2d::GetInvMass ( const VelocityConstraint vc)
inlinenoexcept

◆ GetJointAngle()

Angle box2d::GetJointAngle ( const RevoluteJoint joint)

Get the current joint angle in radians.

◆ GetJointCount()

joint_count_t box2d::GetJointCount ( const World world)
inlinenoexcept

Gets the count of joints in the given world.

Returns
0 or higher.

◆ GetJointSpeed()

AngularVelocity box2d::GetJointSpeed ( const RevoluteJoint joint)

Get the current joint angle speed in radians per second.

◆ GetLength()

template<typename T >
auto box2d::GetLength ( value)
inline

◆ GetLengthSquared() [1/2]

template<typename T >
constexpr auto box2d::GetLengthSquared ( value)
inlinenoexcept

Gets the square of the length/magnitude of the given value. For performance, use this instead of GetLength(T value) (if possible).

Returns
Non-negative value.

◆ GetLengthSquared() [2/2]

template<>
constexpr auto box2d::GetLengthSquared ( Vec3  value)
inlinenoexcept

◆ GetLinearVelocity()

LinearVelocity2D box2d::GetLinearVelocity ( const Body body)
inlinenoexcept

Gets the linear velocity of the center of mass.

Parameters
bodyBody to get the linear velocity for.
Returns
the linear velocity of the center of mass.

◆ GetLinearVelocityFromLocalPoint()

LinearVelocity2D box2d::GetLinearVelocityFromLocalPoint ( const Body body,
const Length2D  localPoint 
)
inlinenoexcept

Gets the linear velocity from a local point.

Parameters
bodyBody to get the linear velocity for.
localPointpoint in local coordinates.
Returns
the world velocity of a point.

◆ GetLinearVelocityFromWorldPoint()

LinearVelocity2D box2d::GetLinearVelocityFromWorldPoint ( const Body body,
const Length2D  worldPoint 
)
inlinenoexcept

Gets the linear velocity from a world point attached to this body.

Parameters
bodyBody to get the linear velocity for.
worldPointpoint in world coordinates.
Returns
the world velocity of a point.

◆ GetLocalInertia()

RotInertia box2d::GetLocalInertia ( const Body body)
inlinenoexcept

Gets the rotational inertia of the body about the local origin.

Returns
the rotational inertia, usually in kg-m^2.

◆ GetLocalPoint() [1/2]

Length2D box2d::GetLocalPoint ( const DistanceProxy proxy,
ContactFeature::Type  type,
ContactFeature::index_t  index 
)

◆ GetLocalPoint() [2/2]

Length2D box2d::GetLocalPoint ( const Body body,
const Length2D  worldPoint 
)
inlinenoexcept

Gets a local point relative to the body's origin given a world point.

Parameters
bodyBody that the returned point should be relative to.
worldPointpoint in world coordinates.
Returns
the corresponding local point relative to the body's origin.

◆ GetLocalVector()

UnitVec2 box2d::GetLocalVector ( const Body body,
const UnitVec2  uv 
)
inlinenoexcept

Gets a locally oriented unit vector given a world oriented unit vector.

Parameters
bodyBody that the returned vector should be relative to.
uvUnit vector in world orientation.
Returns
the corresponding local vector.

◆ GetManifold()

Manifold box2d::GetManifold ( const DistanceProxy proxyA,
const Transformation transformA,
const DistanceProxy proxyB,
const Transformation transformB 
)

◆ GetMass()

Mass box2d::GetMass ( const Body body)
inlinenoexcept

Gets the total mass of the body.

Returns
Value of zero or more representing the body's mass (in kg).
See also
GetInvMass.
SetMassData.

◆ GetMassData() [1/4]

MassData box2d::GetMassData ( const Length  r,
const Density  density,
const Length2D  location 
)

Computes the mass data for a circular shape.

Parameters
rRadius of the circlular shape.
densityAreal density of mass.
locationLocation of the center of the shape.

◆ GetMassData() [2/4]

MassData box2d::GetMassData ( const Length  r,
const Density  density,
const Length2D  v0,
const Length2D  v1 
)

Computes the mass data for a linear shape.

Parameters
rRadius of the vertices of the linear shape.
densityAreal density of mass.
v0Location of vertex zero.
v1Location of vertex one.

Use the fixture's areal mass density times the shape's second moment of area to derive I.

See also
https://en.wikipedia.org/wiki/Second_moment_of_area

◆ GetMassData() [3/4]

MassData box2d::GetMassData ( const Fixture f)

Computes the mass data for the given fixture.

The mass data is based on the density and the shape of the fixture. The rotational inertia is about the shape's origin.

Note
This operation may be expensive.
Parameters
fFixture to compute the mass data for.

◆ GetMassData() [4/4]

MassData box2d::GetMassData ( const Body body)
inlinenoexcept

Gets the mass data of the body.

Returns
a struct containing the mass, inertia and center of the body.

◆ GetMaxRegLinearCorrection()

Length box2d::GetMaxRegLinearCorrection ( const StepConf conf)
inlinenoexcept

◆ GetMaxSeparation() [1/2]

IndexPairSeparation box2d::GetMaxSeparation ( Span< const Length2D verts1,
Span< const UnitVec2 norms1,
Span< const Length2D verts2,
Length  stop = MaxFloat * Meter 
)

Gets the max separation information.

Returns
The index of the vertex and normal from verts1 and norms1, the index of the vertex from verts2 (that had the maximum separation distance from each other in the direction of that normal), and the maximal distance.

◆ GetMaxSeparation() [2/2]

IndexPairSeparation box2d::GetMaxSeparation ( Span< const Length2D verts1,
Span< const UnitVec2 norms1,
const Transformation xf1,
Span< const Length2D verts2,
const Transformation xf2,
Length  stop = MaxFloat * Meter 
)

Gets the max separation information.

Returns
The index of the vertex and normal from verts1 and norms1, the index of the vertex from verts2 (that had the maximum separation distance from each other in the direction of that normal), and the maximal distance.

◆ GetModuloNext()

template<typename T >
constexpr T box2d::GetModuloNext ( value,
count 
)
inlinenoexcept

◆ GetModuloPrev()

template<typename T >
constexpr T box2d::GetModuloPrev ( value,
count 
)
inlinenoexcept

◆ GetName()

const char * box2d::GetName ( Manifold::Type  type)
noexcept

◆ GetNextIndex()

child_count_t box2d::GetNextIndex ( const ChainShape shape,
child_count_t  index 
)
inlinenoexcept

◆ GetNormal()

UnitVec2 box2d::GetNormal ( const VelocityConstraint vc)
inlinenoexcept

Gets the normal of the velocity constraint contact in world coordinates.

Note
This value is set via the velocity constraint's SetNormal method.
Returns
Contact normal (in world coordinates) if previously set, an invalid value otherwise.

◆ GetNormalImpulseAtPoint()

Momentum box2d::GetNormalImpulseAtPoint ( const VelocityConstraint vc,
VelocityConstraint::size_type  index 
)
inline

◆ GetNormalImpulses()

Momentum2D box2d::GetNormalImpulses ( const VelocityConstraint vc)
inline

◆ GetNormalized()

Angle box2d::GetNormalized ( Angle  value)
inline

◆ GetNormalMassAtPoint()

Mass box2d::GetNormalMassAtPoint ( const VelocityConstraint vc,
VelocityConstraint::size_type  index 
)
inline

◆ GetPerimeter()

constexpr Length box2d::GetPerimeter ( const AABB  aabb)
noexcept

Gets the perimeter length of the AABB.

Returns
Twice the sum of the width and height.

◆ GetPointDelta()

constexpr Length2D box2d::GetPointDelta ( const SimplexEdge sv)
inline

Gets "w".

Returns
2D vector value of wB minus wA.

◆ GetPointRelPosA()

Length2D box2d::GetPointRelPosA ( const VelocityConstraint vc,
VelocityConstraint::size_type  index 
)
inline

◆ GetPointRelPosB()

Length2D box2d::GetPointRelPosB ( const VelocityConstraint vc,
VelocityConstraint::size_type  index 
)
inline

◆ GetPointStates()

void box2d::GetPointStates ( PointStateArray state1,
PointStateArray state2,
const Manifold manifold1,
const Manifold manifold2 
)

Computes the point states given two manifolds. The states pertain to the transition from manifold1 to manifold2. So state1 is either persist or remove while state2 is either add or persist.

◆ GetPolarMoment()

SecondMomentOfArea box2d::GetPolarMoment ( Span< const Length2D vertices)

Gets the polar moment of the area enclosed by the given vertices.

Warning
Behavior is undefined if given collection has less than 3 vertices.
Parameters
verticesCollection of three or more vertices.

◆ GetPosition()

Position box2d::GetPosition ( const Position  pos0,
const Position  pos1,
const RealNum  beta 
)
inlinenoexcept

Gets the position between two positions at a given unit interval.

Parameters
pos0Position at unit interval value of 0.
pos1Position at unit interval value of 1.
betaUnit interval (value between 0 and 1) of travel between pos0 and pos1.
Returns
pos0 if pos0 == pos1 or beta == 0, pos1 if beta == 1, or at the given unit interval value between pos0 and pos1.

◆ GetPosition1()

Position box2d::GetPosition1 ( const Body body)
inlinenoexcept

◆ GetPSM() [1/2]

PositionSolverManifold box2d::GetPSM ( const Manifold manifold,
Manifold::size_type  index,
Position  pos_a,
Length2D  lc_ctr_a,
Position  pos_b,
Length2D  lc_ctr_b 
)
inline

Gets the normal-point-separation data in world coordinates for the given inputs.

Note
The returned normal is in the direction of shape A to shape B.
The returned separation distance does not account for vertex radiuses. It's simply the separation between the points of the manifold. To account for the vertex radiuses, the total vertex radius must be subtracted from this separation distance.

◆ GetPSM() [2/2]

PositionSolverManifold box2d::GetPSM ( const Manifold manifold,
Manifold::size_type  index,
const Transformation xfA,
const Transformation xfB 
)

Gets the normal-point-separation data in world coordinates for the given inputs.

Note
The returned normal is in the direction of shape A to shape B.
The returned separation distance does not account for vertex radiuses. It's simply the separation between the points of the manifold. To account for the vertex radiuses, the total vertex radius must be subtracted from this separation distance.

◆ GetRevPerpendicular() [1/2]

constexpr UnitVec2 box2d::GetRevPerpendicular ( const UnitVec2  vector)
inlinenoexcept

Gets a vector counter-clockwise (reverse-clockwise) perpendicular to the given vector.

This takes a vector of form (x, y) and returns the vector (-y, x).

Parameters
vectorVector to return a counter-clockwise perpendicular equivalent for.
Returns
A counter-clockwise 90-degree rotation of the given vector.
See also
GetFwdPerpendicular.

◆ GetRevPerpendicular() [2/2]

template<class T >
constexpr auto box2d::GetRevPerpendicular ( const T  vector)
inlinenoexcept

Gets a vector counter-clockwise (reverse-clockwise) perpendicular to the given vector.

This takes a vector of form (x, y) and returns the vector (-y, x).

Parameters
vectorVector to return a counter-clockwise perpendicular equivalent for.
Returns
A counter-clockwise 90-degree rotation of the given vector.
See also
GetFwdPerpendicular.

◆ GetRevRotationalAngle()

constexpr Angle box2d::GetRevRotationalAngle ( Angle  a1,
Angle  a2 
)
inlinenoexcept

Gets the reverse (counter) clockwise rotational angle to go from angle 1 to angle 2.

Note
The given angles must be normalized between -Pi to Pi radians.
Returns
Angular rotation in the counter clockwise direction to go from angle 1 to angle 2.

◆ GetRotInertia()

RotInertia box2d::GetRotInertia ( const Body body)
inlinenoexcept

Gets the rotational inertia of the body.

Parameters
bodyBody to get the rotational inertia for.
Returns
the rotational inertia, usually in kg-m^2.

◆ GetScaledDelta()

Length2D box2d::GetScaledDelta ( const Simplex simplex,
Simplex::size_type  index 
)
inline

◆ GetShapeCount()

size_t box2d::GetShapeCount ( const World world)
noexcept

Gets the count of unique shapes in the given world.

◆ GetSupportIndex()

DistanceProxy::size_type box2d::GetSupportIndex ( const DistanceProxy proxy,
const Length2D  d 
)
noexcept

Gets the supporting vertex index in the given direction for the given distance proxy.

This finds the vertex that's most significantly in the direction of the given vector and returns its index.

Note
0 is returned for a given zero length direction vector.
Parameters
proxyDistance proxy object to find index in if a valid index exists for it.
dDirection vector to find index for.
Returns
InvalidIndex if d is invalid or the count of vertices is zero, otherwise a value from 0 to one less than count.
See also
GetVertexCount().

< Index of vertex that when dotted with d has the max value.

< Max dot value.

◆ GetSymInverse33()

constexpr Mat33 box2d::GetSymInverse33 ( const Mat33 value)
inlinenoexcept

Get the symmetric inverse of this matrix as a 3-by-3. Returns the zero matrix if singular.

◆ GetTangent()

UnitVec2 box2d::GetTangent ( const VelocityConstraint vc)
inlinenoexcept

◆ GetTangentImpulseAtPoint()

Momentum box2d::GetTangentImpulseAtPoint ( const VelocityConstraint vc,
VelocityConstraint::size_type  index 
)
inline

◆ GetTangentImpulses()

Momentum2D box2d::GetTangentImpulses ( const VelocityConstraint vc)
inline

◆ GetTangentMassAtPoint()

Mass box2d::GetTangentMassAtPoint ( const VelocityConstraint vc,
VelocityConstraint::size_type  index 
)
inline

◆ GetToiViaSat()

TOIOutput box2d::GetToiViaSat ( const DistanceProxy proxyA,
const Sweep sweepA,
const DistanceProxy proxyB,
const Sweep sweepB,
const ToiConf  conf = GetDefaultToiConf() 
)

Gets the time of impact for two disjoint convex sets using the Separating Axis Theorem.

Computes the upper bound on time before two shapes penetrate too much. Time is represented as a fraction between [0,tMax]. This uses a swept separating axis and may miss some intermediate, non-tunneling collision. If you change the time interval, you should call this function again.

See also
https://en.wikipedia.org/wiki/Hyperplane_separation_theorem
Precondition
The given sweeps are both at the same alpha0.
Warning
Behavior is undefined if the given sweeps are not at the same alpha0.
Note
Uses Distance to compute the contact point and normal at the time of impact.
This only works for two disjoint convex sets.
Parameters
proxyAProxy A. The proxy's vertex count must be 1 or more.
sweepASweep A. Sweep of motion for shape represented by proxy A.
proxyBProxy B. The proxy's vertex count must be 1 or more.
sweepBSweep B. Sweep of motion for shape represented by proxy B.
confConfiguration details for on calculation. Like the targetted depth of penetration.
Returns
Time of impact output data.

◆ GetTorque()

Torque box2d::GetTorque ( const Body body)
inlinenoexcept

◆ GetTransform0()

Transformation box2d::GetTransform0 ( const Sweep sweep)
inlinenoexcept

Gets the transform at "time" zero.

Note
This is like calling GetTransformation(sweep, 0), except more efficiently.
See also
GetTransformation(const Sweep& sweep, RealNum beta).
Parameters
sweepSweep data to get the transform from.
Returns
Transformation of the given sweep at time zero.

◆ GetTransform1()

Transformation box2d::GetTransform1 ( const Sweep sweep)
inlinenoexcept

Gets the transform at "time" one.

Note
This is like calling GetTransformation(sweep, 1.0), except more efficiently.
See also
GetTransformation(const Sweep& sweep, RealNum beta).
Parameters
sweepSweep data to get the transform from.
Returns
Transformation of the given sweep at time one.

◆ GetTransformation() [1/4]

Transformation box2d::GetTransformation ( const Fixture f)
noexcept

Gets the transformation associated with the given fixture.

Warning
Behavior is undefined if the fixture doesn't have an associated body - i.e. behavior is undefined if the fixture has nullptr as its associated body.

◆ GetTransformation() [2/4]

constexpr Transformation box2d::GetTransformation ( const Length2D  ctr,
const UnitVec2  rot,
const Length2D  localCtr 
)
inlinenoexcept

◆ GetTransformation() [3/4]

Transformation box2d::GetTransformation ( const Position  pos,
const Length2D  local_ctr 
)
inlinenoexcept

◆ GetTransformation() [4/4]

Transformation box2d::GetTransformation ( const Sweep sweep,
const RealNum  beta 
)
inlinenoexcept

Gets the interpolated transform at a specific time.

Parameters
sweepSweep data to get the transform from.
betaTime factor in [0,1], where 0 indicates alpha0.
Returns
Transformation of the given sweep at the specified time.

◆ GetUnitVector() [1/3]

template<class T >
UnitVec2 box2d::GetUnitVector ( const Vector2D< T >  value,
const UnitVec2  fallback = UnitVec2::GetDefaultFallback() 
)
inline

Gets the unit vector for the given value.

Parameters
valueValue to get the unit vector for.
fallbackFallback unit vector value to use in case a unit vector can't effectively be calculated from the given value.
Returns
value divided by its length if length not almost zero otherwise invalid value.
See also
almost_equal.

◆ GetUnitVector() [2/3]

template<class T >
UnitVec2 box2d::GetUnitVector ( const Vector2D< T >  value,
T &  magnitude,
const UnitVec2  fallback = UnitVec2::GetDefaultFallback() 
)
inline

Gets the unit vector for the given value.

Parameters
valueValue to get the unit vector for.
magnitudeReturns the calculated magnitude of the given vector.
fallbackFallback unit vector value to use in case a unit vector can't effectively be calculated from the given value.
Returns
value divided by its length if length not almost zero otherwise invalid value.
See also
almost_equal.

◆ GetUnitVector() [3/3]

template<>
UnitVec2 box2d::GetUnitVector ( const Vector2D< RealNum value,
RealNum magnitude,
const UnitVec2  fallback 
)
inline

◆ GetVec2()

constexpr Vec2 box2d::GetVec2 ( const UnitVec2  value)
inline

◆ GetVelocity()

Velocity box2d::GetVelocity ( const Body body,
Time  h 
)
noexcept

Gets the velocity of the body after the given time accounting for the body's acceleration.

Warning
Behavior is undefined if the given elapsed time is an invalid value (like NaN).
Parameters
bodyBody to get the velocity for.
hTime elapsed to get velocity for. Behavior is undefined if this value is invalid.

◆ GetVelocityBiasAtPoint()

LinearVelocity box2d::GetVelocityBiasAtPoint ( const VelocityConstraint vc,
VelocityConstraint::size_type  index 
)
inline

◆ GetVertexFaceContactFeature()

constexpr ContactFeature box2d::GetVertexFaceContactFeature ( ContactFeature::index_t  a,
ContactFeature::index_t  b 
)
noexcept

◆ GetVertexRadius()

Length box2d::GetVertexRadius ( const Shape shape)
inlinenoexcept

Gets the vertex radius of the given shape (in meters).

Gets the radius (in meters) of every vertex of this shape. This is used for collision handling.

Note
This value should never be less than zero.

◆ GetVertexVertexContactFeature()

constexpr ContactFeature box2d::GetVertexVertexContactFeature ( ContactFeature::index_t  a,
ContactFeature::index_t  b 
)
noexcept

◆ GetWitnessPoints()

WitnessPoints box2d::GetWitnessPoints ( const Simplex simplex)
noexcept

Gets the witness points of the given simplex.

◆ GetWorldIndex() [1/2]

size_t box2d::GetWorldIndex ( const Joint joint)

◆ GetWorldIndex() [2/2]

box2d::size_t box2d::GetWorldIndex ( const Body body)

◆ GetWorldManifold() [1/2]

WorldManifold box2d::GetWorldManifold ( const Manifold manifold,
const Transformation xfA,
const Length  radiusA,
const Transformation xfB,
const Length  radiusB 
)

Gets the world manifold for the given data.

Precondition
The given manifold input has between 0 and 2 points.
Parameters
manifoldManifold to use. Uses the manifold's type, local point, local normal, point-count, and the indexed-points' local point data.
xfATransformation A.
radiusARadius of shape A.
xfBTransformation B.
radiusBRadius of shape B.
Returns
World manifold value for the given inputs which will have the same number of points as the given manifold has. The returned world manifold points will be the mid-points of the manifold intersection.

◆ GetWorldManifold() [2/2]

WorldManifold box2d::GetWorldManifold ( const Contact contact)

Gets the world manifold for the given data.

Note
This is a convenience function that in turn calls the GetWorldManifold(const Manifold&, const Transformation&, const RealNum, const Transformation& xfB, const RealNum) function.
Parameters
contactContact to return a world manifold for.
Returns
World manifold value for the given inputs which will have the same number of points as the given manifold has. The returned world manifold points will be the mid-points of the contact's intersection.

◆ GetWorldPoint()

Length2D box2d::GetWorldPoint ( const Body body,
const Length2D  localPoint 
)
inlinenoexcept

Gets the world coordinates of a point given in coordinates relative to the body's origin.

Parameters
bodyBody that the given point is relative to.
localPointa point measured relative the the body's origin.
Returns
the same point expressed in world coordinates.

◆ GetWorldVector() [1/2]

Length2D box2d::GetWorldVector ( const Body body,
const Length2D  localVector 
)
inlinenoexcept

Gets the world coordinates of a vector given the local coordinates.

Parameters
bodyBody that the given vector is relative to.
localVectora vector fixed in the body.
Returns
the same vector expressed in world coordinates.

◆ GetWorldVector() [2/2]

UnitVec2 box2d::GetWorldVector ( const Body body,
const UnitVec2  localVector 
)
inlinenoexcept

◆ GetX() [1/2]

template<typename TYPE >
constexpr Vector2D<TYPE>::data_type box2d::GetX ( const Vector2D< TYPE >  value)
inline

◆ GetX() [2/2]

constexpr UnitVec2::data_type box2d::GetX ( const UnitVec2  value)
inline

◆ GetXAxis()

constexpr UnitVec2 box2d::GetXAxis ( UnitVec2  rot)
inlinenoexcept

Get the x-axis.

◆ GetY() [1/2]

template<typename TYPE >
constexpr Vector2D<TYPE>::data_type box2d::GetY ( const Vector2D< TYPE >  value)
inline

◆ GetY() [2/2]

constexpr UnitVec2::data_type box2d::GetY ( const UnitVec2  value)
inline

◆ GetYAxis()

constexpr UnitVec2 box2d::GetYAxis ( UnitVec2  rot)
inlinenoexcept

Get the u-axis ("u"??? is that a typo??? Anyway, this is the reverse perpendicular vector of rot as a directional vector)

◆ HasSensor()

bool box2d::HasSensor ( const Contact contact)
noexcept

◆ InverseRotate() [1/2]

constexpr UnitVec2 box2d::InverseRotate ( const UnitVec2  vector,
const UnitVec2 angle 
)
inlinenoexcept

Inverse rotate a vector.

◆ InverseRotate() [2/2]

template<class T >
constexpr auto box2d::InverseRotate ( const Vector2D< T >  vector,
const UnitVec2 angle 
)
inlinenoexcept

Inverse rotate a vector.

This is the inverse of rotating a vector - it undoes what rotate does.

See also
Rotate.

◆ InverseTransform() [1/2]

constexpr Vec2 box2d::InverseTransform ( const Vec2  v,
const Mat22 A 
)
inlinenoexcept

Multiply a matrix transpose times a vector. If a rotation matrix is provided, then this transforms the vector from one frame to another (inverse transform).

◆ InverseTransform() [2/2]

constexpr Length2D box2d::InverseTransform ( const Length2D  v,
const Transformation  T 
)
inlinenoexcept

Inverse transforms the given 2-D vector with the given transformation.

Inverse translate and rotate the given 2-D vector according to the translation and rotation defined by the given transformation.

Note
Passing the output of this function to Transform (with the same transformation again) will result in the original vector being returned.
See also
Transform.
Parameters
v2-D vector to inverse transform (inverse translate and inverse rotate).
TTransformation (a translation and rotation) to invertedly apply to the given vector.
Returns
Inverse transformed vector.

◆ Invert()

constexpr Mat22 box2d::Invert ( const Mat22  value)
noexcept

◆ IsActive()

bool box2d::IsActive ( const Contact contact)
noexcept

◆ IsEnabled()

bool box2d::IsEnabled ( const Joint j)
noexcept

Short-cut function to determine if both bodies are enabled.

◆ IsFullOfBodies()

bool box2d::IsFullOfBodies ( const Island island)
inline

◆ IsFullOfContacts()

bool box2d::IsFullOfContacts ( const Island island)
inline

◆ IsImpenetrable()

bool box2d::IsImpenetrable ( const Contact contact)
noexcept

◆ IsLooped()

bool box2d::IsLooped ( const ChainShape shape)
inlinenoexcept

◆ IsMaxTranslationWithinTolerance()

bool box2d::IsMaxTranslationWithinTolerance ( const StepConf conf)
noexcept

◆ IsUnderActive()

bool box2d::IsUnderActive ( Velocity  velocity,
LinearVelocity  linSleepTol,
AngularVelocity  angSleepTol 
)
inlinenoexcept

◆ IsValid() [1/10]

template<typename TYPE >
constexpr bool box2d::IsValid ( const Vector2D< TYPE > &  value)
inlinenoexcept

Does this vector contain finite coordinates?

◆ IsValid() [2/10]

template<>
constexpr bool box2d::IsValid ( const Vec3 value)
inlinenoexcept

Does this vector contain finite coordinates?

◆ IsValid() [3/10]

template<>
constexpr bool box2d::IsValid ( const Mat22 value)
inlinenoexcept

◆ IsValid() [4/10]

template<typename T >
constexpr bool box2d::IsValid ( const T &  value)
inlinenoexcept

◆ IsValid() [5/10]

template<>
constexpr bool box2d::IsValid ( const Manifold value)
inlinenoexcept

◆ IsValid() [6/10]

template<>
constexpr bool box2d::IsValid ( const size_t x)
inlinenoexcept

◆ IsValid() [7/10]

template<>
constexpr bool box2d::IsValid ( const UnitVec2 value)
inlinenoexcept

◆ IsValid() [8/10]

template<>
constexpr bool box2d::IsValid ( const Transformation value)
inlinenoexcept

◆ IsValid() [9/10]

template<>
constexpr bool box2d::IsValid ( const Position value)
inlinenoexcept

◆ IsValid() [10/10]

template<>
constexpr bool box2d::IsValid ( const Velocity value)
inlinenoexcept

◆ Max()

template<typename T >
constexpr T box2d::Max ( a,
b 
)
inlinenoexcept

◆ max_list_size()

template<typename T >
constexpr size_t box2d::max_list_size ( )

Maximum list size.

◆ max_list_size< Body >()

template<>
constexpr size_t box2d::max_list_size< Body > ( )

◆ max_list_size< Contact >()

template<>
constexpr size_t box2d::max_list_size< Contact > ( )

◆ max_list_size< Joint >()

template<>
constexpr size_t box2d::max_list_size< Joint > ( )

◆ Min()

template<typename T >
constexpr T box2d::Min ( a,
b 
)
inlinenoexcept

◆ MixFriction()

RealNum box2d::MixFriction ( RealNum  friction1,
RealNum  friction2 
)
inline

Friction mixing law. The idea is to allow either fixture to drive the resulting friction to zero. For example, anything slides on ice.

◆ MixRestitution()

RealNum box2d::MixRestitution ( RealNum  restitution1,
RealNum  restitution2 
)
inlinenoexcept

Restitution mixing law. The idea is allow for anything to bounce off an inelastic surface. For example, a superball bounces on anything.

◆ Mul() [1/2]

constexpr Mat22 box2d::Mul ( const Mat22 A,
const Mat22 B 
)
inlinenoexcept

◆ Mul() [2/2]

constexpr Transformation box2d::Mul ( const Transformation A,
const Transformation B 
)
inlinenoexcept

◆ MulT() [1/2]

constexpr Mat22 box2d::MulT ( const Mat22 A,
const Mat22 B 
)
inlinenoexcept

◆ MulT() [2/2]

constexpr Transformation box2d::MulT ( const Transformation A,
const Transformation B 
)
inlinenoexcept

◆ NextPowerOfTwo()

std::uint64_t box2d::NextPowerOfTwo ( std::uint64_t  x)
inline

"Next Largest Power of 2 Given a binary integer value x, the next largest power of 2 can be computed by a SWAR algorithm that recursively "folds" the upper bits into the lower bits. This process yields a bit vector with the same most significant 1 as x, but all 1's below it. Adding 1 to that value yields the next largest power of 2. For a 64-bit value:"

◆ Normalize()

RealNum box2d::Normalize ( Vec2 vector)
inline

Converts the given vector into a unit vector and returns its original length.

◆ NOT_USED()

template<class... T>
void box2d::NOT_USED ( T &&  ...)

◆ operator!=() [1/15]

constexpr bool box2d::operator!= ( ProxyIdPair  lhs,
ProxyIdPair  rhs 
)
inline

◆ operator!=() [2/15]

constexpr bool box2d::operator!= ( IndexPair  lhs,
IndexPair  rhs 
)
inline

◆ operator!=() [3/15]

constexpr bool box2d::operator!= ( ContactFeature  lhs,
ContactFeature  rhs 
)
noexcept

◆ operator!=() [4/15]

template<typename TYPE >
constexpr bool box2d::operator!= ( const Vector2D< TYPE >  a,
const Vector2D< TYPE >  b 
)
inlinenoexcept

◆ operator!=() [5/15]

constexpr bool box2d::operator!= ( const SimplexEdge lhs,
const SimplexEdge rhs 
)
inline

◆ operator!=() [6/15]

bool box2d::operator!= ( const BlockAllocator a,
const BlockAllocator b 
)
inline

◆ operator!=() [7/15]

constexpr bool box2d::operator!= ( const UnitVec2  a,
const UnitVec2  b 
)
inlinenoexcept

◆ operator!=() [8/15]

constexpr bool box2d::operator!= ( const AABB  lhs,
const AABB  rhs 
)

◆ operator!=() [9/15]

bool box2d::operator!= ( const Manifold::Point lhs,
const Manifold::Point rhs 
)

◆ operator!=() [10/15]

bool box2d::operator!= ( const Manifold lhs,
const Manifold rhs 
)

◆ operator!=() [11/15]

constexpr bool box2d::operator!= ( Fixed32  lhs,
Fixed32  rhs 
)
noexcept

◆ operator!=() [12/15]

constexpr bool box2d::operator!= ( const Vec3  lhs,
const Vec3  rhs 
)
inlinenoexcept

◆ operator!=() [13/15]

constexpr bool box2d::operator!= ( Transformation  lhs,
Transformation  rhs 
)
inlinenoexcept

◆ operator!=() [14/15]

constexpr bool box2d::operator!= ( const Position lhs,
const Position rhs 
)
inline

◆ operator!=() [15/15]

constexpr bool box2d::operator!= ( const Velocity lhs,
const Velocity rhs 
)
inline

◆ operator%()

constexpr Fixed64 box2d::operator% ( Fixed32  lhs,
Fixed32  rhs 
)
noexcept

◆ operator*() [1/10]

template<typename TYPE1 , typename TYPE2 , typename OUT_TYPE = decltype(TYPE1{0} * TYPE2{0})>
constexpr Vector2D<OUT_TYPE> box2d::operator* ( const TYPE1  s,
const Vector2D< TYPE2 >  a 
)
inlinenoexcept

◆ operator*() [2/10]

template<typename TYPE1 , typename TYPE2 , typename OUT_TYPE = decltype(TYPE1{0} * TYPE2{0})>
constexpr Vector2D<OUT_TYPE> box2d::operator* ( const Vector2D< TYPE1 >  a,
const TYPE2  s 
)
inlinenoexcept

◆ operator*() [3/10]

constexpr Fixed64 box2d::operator* ( Fixed32  lhs,
Fixed32  rhs 
)
noexcept

◆ operator*() [4/10]

template<class T >
constexpr Vector2D<T> box2d::operator* ( const T  s,
const UnitVec2  u 
)
inlinenoexcept

◆ operator*() [5/10]

template<class T >
constexpr Vector2D<T> box2d::operator* ( const UnitVec2  u,
const T  s 
)
inlinenoexcept

◆ operator*() [6/10]

constexpr Vec3 box2d::operator* ( const RealNum  s,
const Vec3  a 
)
inlinenoexcept

◆ operator*() [7/10]

constexpr Position box2d::operator* ( const Position pos,
const RealNum  scalar 
)
inline

◆ operator*() [8/10]

constexpr Position box2d::operator* ( const RealNum  scalar,
const Position pos 
)
inline

◆ operator*() [9/10]

constexpr Velocity box2d::operator* ( const Velocity lhs,
const RealNum  rhs 
)
inline

◆ operator*() [10/10]

constexpr Velocity box2d::operator* ( const RealNum  lhs,
const Velocity rhs 
)
inline

◆ operator*=() [1/3]

template<typename TYPE >
constexpr Vector2D<TYPE>& box2d::operator*= ( Vector2D< TYPE > &  lhs,
const RealNum  rhs 
)
noexcept

◆ operator*=() [2/3]

constexpr Vec3& box2d::operator*= ( Vec3 lhs,
const RealNum  rhs 
)
noexcept

◆ operator*=() [3/3]

constexpr Velocity& box2d::operator*= ( Velocity lhs,
const RealNum  rhs 
)
inline

◆ operator+() [1/11]

PositionSolution box2d::operator+ ( PositionSolution  lhs,
PositionSolution  rhs 
)
inline

◆ operator+() [2/11]

template<typename TYPE >
constexpr Vector2D<TYPE> box2d::operator+ ( const Vector2D< TYPE >  a,
const Vector2D< TYPE >  b 
)
inlinenoexcept

Add two vectors component-wise.

◆ operator+() [3/11]

template<typename T , std::size_t S>
ArrayList<T, S> box2d::operator+ ( ArrayList< T, S >  lhs,
const typename ArrayList< T, S >::data_type &  rhs 
)

◆ operator+() [4/11]

constexpr Fixed64 box2d::operator+ ( Fixed32  lhs,
Fixed32  rhs 
)
noexcept

◆ operator+() [5/11]

constexpr Vec2 box2d::operator+ ( const UnitVec2  lhs,
const UnitVec2  rhs 
)
inlinenoexcept

◆ operator+() [6/11]

constexpr Vec3 box2d::operator+ ( const Vec3  a,
const Vec3  b 
)
inlinenoexcept

Add two vectors component-wise.

◆ operator+() [7/11]

constexpr Mat22 box2d::operator+ ( const Mat22  A,
const Mat22  B 
)
inlinenoexcept

◆ operator+() [8/11]

constexpr Position box2d::operator+ ( const Position value)
inline

◆ operator+() [9/11]

constexpr Position box2d::operator+ ( const Position lhs,
const Position rhs 
)
inline

◆ operator+() [10/11]

constexpr Velocity box2d::operator+ ( const Velocity lhs,
const Velocity rhs 
)
inline

◆ operator+() [11/11]

constexpr Velocity box2d::operator+ ( const Velocity value)
inline

◆ operator+=() [1/5]

template<typename TYPE >
constexpr Vector2D<TYPE>& box2d::operator+= ( Vector2D< TYPE > &  lhs,
const Vector2D< TYPE >  rhs 
)
noexcept

Increment the left hand side value by the right hand side value.

◆ operator+=() [2/5]

template<typename T , std::size_t S>
ArrayList<T, S>& box2d::operator+= ( ArrayList< T, S > &  lhs,
const typename ArrayList< T, S >::data_type &  rhs 
)

◆ operator+=() [3/5]

constexpr Vec3& box2d::operator+= ( Vec3 lhs,
const Vec3 rhs 
)
noexcept

◆ operator+=() [4/5]

constexpr Position& box2d::operator+= ( Position lhs,
const Position rhs 
)
inline

◆ operator+=() [5/5]

constexpr Velocity& box2d::operator+= ( Velocity lhs,
const Velocity rhs 
)
inline

◆ operator-() [1/9]

PositionSolution box2d::operator- ( PositionSolution  lhs,
PositionSolution  rhs 
)
inline

◆ operator-() [2/9]

template<typename TYPE >
constexpr Vector2D<TYPE> box2d::operator- ( const Vector2D< TYPE >  a,
const Vector2D< TYPE >  b 
)
inlinenoexcept

Subtract two vectors component-wise.

◆ operator-() [3/9]

constexpr Fixed64 box2d::operator- ( Fixed32  lhs,
Fixed32  rhs 
)
noexcept

◆ operator-() [4/9]

constexpr Vec2 box2d::operator- ( const UnitVec2  lhs,
const UnitVec2  rhs 
)
inlinenoexcept

◆ operator-() [5/9]

constexpr Vec3 box2d::operator- ( const Vec3  a,
const Vec3  b 
)
inlinenoexcept

Subtract two vectors component-wise.

◆ operator-() [6/9]

constexpr Position box2d::operator- ( const Position value)
inline

◆ operator-() [7/9]

constexpr Position box2d::operator- ( const Position lhs,
const Position rhs 
)
inline

◆ operator-() [8/9]

constexpr Velocity box2d::operator- ( const Velocity lhs,
const Velocity rhs 
)
inline

◆ operator-() [9/9]

constexpr Velocity box2d::operator- ( const Velocity value)
inline

◆ operator-=() [1/4]

template<typename TYPE >
constexpr Vector2D<TYPE>& box2d::operator-= ( Vector2D< TYPE > &  lhs,
const Vector2D< TYPE >  rhs 
)
noexcept

Decrement the left hand side value by the right hand side value.

◆ operator-=() [2/4]

constexpr Vec3& box2d::operator-= ( Vec3 lhs,
const Vec3 rhs 
)
noexcept

◆ operator-=() [3/4]

constexpr Position& box2d::operator-= ( Position lhs,
const Position rhs 
)
inline

◆ operator-=() [4/4]

constexpr Velocity& box2d::operator-= ( Velocity lhs,
const Velocity rhs 
)
inline

◆ operator/() [1/4]

template<typename TYPE1 , typename TYPE2 , typename OUT_TYPE = decltype(TYPE1{0} / TYPE2{0})>
constexpr Vector2D<OUT_TYPE> box2d::operator/ ( const Vector2D< TYPE1 >  a,
const TYPE2  s 
)
noexcept

◆ operator/() [2/4]

constexpr Fixed64 box2d::operator/ ( Fixed32  lhs,
Fixed32  rhs 
)
noexcept

◆ operator/() [3/4]

constexpr Vec2 box2d::operator/ ( const UnitVec2  u,
const UnitVec2::data_type  s 
)
inlinenoexcept

◆ operator/() [4/4]

constexpr Velocity box2d::operator/ ( const Velocity lhs,
const RealNum  rhs 
)
inline

◆ operator/=() [1/2]

template<typename TYPE >
constexpr Vector2D<TYPE>& box2d::operator/= ( Vector2D< TYPE > &  lhs,
const RealNum  rhs 
)
noexcept

◆ operator/=() [2/2]

constexpr Velocity& box2d::operator/= ( Velocity lhs,
const RealNum  rhs 
)
inline

◆ operator<()

constexpr bool box2d::operator< ( Fixed32  lhs,
Fixed32  rhs 
)
noexcept

◆ operator<<() [1/3]

std::ostream & box2d::operator<< ( ::std::ostream &  os,
const Vec2 value 
)

◆ operator<<() [2/3]

std::ostream & box2d::operator<< ( ::std::ostream &  os,
const UnitVec2 value 
)

◆ operator<<() [3/3]

std::ostream & box2d::operator<< ( ::std::ostream &  os,
const Fixed32 value 
)

◆ operator<=()

constexpr bool box2d::operator<= ( Fixed32  lhs,
Fixed32  rhs 
)
noexcept

◆ operator==() [1/15]

constexpr bool box2d::operator== ( ProxyIdPair  lhs,
ProxyIdPair  rhs 
)
inline

◆ operator==() [2/15]

constexpr bool box2d::operator== ( IndexPair  lhs,
IndexPair  rhs 
)
inline

◆ operator==() [3/15]

constexpr bool box2d::operator== ( ContactFeature  lhs,
ContactFeature  rhs 
)
noexcept

◆ operator==() [4/15]

template<typename TYPE >
constexpr bool box2d::operator== ( const Vector2D< TYPE >  a,
const Vector2D< TYPE >  b 
)
inlinenoexcept

◆ operator==() [5/15]

constexpr bool box2d::operator== ( const SimplexEdge lhs,
const SimplexEdge rhs 
)
inline

◆ operator==() [6/15]

bool box2d::operator== ( const BlockAllocator a,
const BlockAllocator b 
)
inline

◆ operator==() [7/15]

constexpr bool box2d::operator== ( const UnitVec2  a,
const UnitVec2  b 
)
inlinenoexcept

◆ operator==() [8/15]

constexpr bool box2d::operator== ( const AABB  lhs,
const AABB  rhs 
)

◆ operator==() [9/15]

bool box2d::operator== ( const Manifold::Point lhs,
const Manifold::Point rhs 
)

◆ operator==() [10/15]

bool box2d::operator== ( const Manifold lhs,
const Manifold rhs 
)

Equality operator.

Note
In-so-far as manifold points are concerned, order doesn't matter; only whether the two manifolds have the same point set.

◆ operator==() [11/15]

constexpr bool box2d::operator== ( Fixed32  lhs,
Fixed32  rhs 
)
noexcept

◆ operator==() [12/15]

constexpr bool box2d::operator== ( const Vec3  lhs,
const Vec3  rhs 
)
inlinenoexcept

◆ operator==() [13/15]

constexpr bool box2d::operator== ( Transformation  lhs,
Transformation  rhs 
)
inlinenoexcept

◆ operator==() [14/15]

constexpr bool box2d::operator== ( const Position lhs,
const Position rhs 
)
inline

◆ operator==() [15/15]

constexpr bool box2d::operator== ( const Velocity lhs,
const Velocity rhs 
)
inline

◆ operator>()

constexpr bool box2d::operator> ( Fixed32  lhs,
Fixed32  rhs 
)
noexcept

◆ operator>=()

constexpr bool box2d::operator>= ( Fixed32  lhs,
Fixed32  rhs 
)
noexcept

◆ RayCast() [1/2]

RayCastOutput box2d::RayCast ( const AABB aabb,
const RayCastInput input 
)

◆ RayCast() [2/2]

RayCastOutput box2d::RayCast ( const Fixture f,
const RayCastInput input,
child_count_t  childIndex 
)

Cast a ray against the shape of the given fixture.

Parameters
fFixture.
inputthe ray-cast input parameters.
childIndexChild index.

◆ realloc() [1/2]

void * box2d::realloc ( void *  ptr,
size_t  new_size 
)

Implement this function to use your own memory allocator.

◆ realloc() [2/2]

template<typename T >
T* box2d::realloc ( T *  ptr,
size_t  size 
)

◆ ResetFriction()

void box2d::ResetFriction ( Contact contact)

Resets the friction mixture to the default value.

◆ ResetRestitution()

void box2d::ResetRestitution ( Contact contact)
noexcept

Reset the restitution to the default value.

◆ Rotate() [1/2]

constexpr UnitVec2 box2d::Rotate ( const UnitVec2  vector,
const UnitVec2 angle 
)
inlinenoexcept

Rotates a vector by a given angle.

◆ Rotate() [2/2]

template<class T >
constexpr auto box2d::Rotate ( const Vector2D< T >  vector,
const UnitVec2 angle 
)
inlinenoexcept

Rotates a vector by a given angle.

See also
InverseRotate.

◆ RotateAboutLocalPoint()

void box2d::RotateAboutLocalPoint ( Body body,
Angle  amount,
Length2D  localPoint 
)

Rotates a body a given amount around a point in body local coordinates.

This changes both the linear and angular positions of the body.

Note
Manipulating a body's position this way may cause non-physical behavior.
This is a convenience function that translates the local point into world coordinates and then calls the RotateAboutWorldPoint function.
Parameters
bodyBody to rotate.
amountAmount to rotate body by (in counter-clockwise direction).
localPointPoint in local coordinates.

◆ RotateAboutWorldPoint()

void box2d::RotateAboutWorldPoint ( Body body,
Angle  amount,
Length2D  worldPoint 
)

Rotates a body a given amount around a point in world coordinates.

This changes both the linear and angular positions of the body.

Note
Manipulating a body's position this way may cause non-physical behavior.
Parameters
bodyBody to rotate.
amountAmount to rotate body by (in counter-clockwise direction).
worldPointPoint in world coordinates.

◆ round() [1/7]

template<typename T >
T box2d::round ( value,
unsigned  precision = 100000 
)
inline

◆ round() [2/7]

template<>
float box2d::round ( float  value,
uint32_t  precision 
)
inline

◆ round() [3/7]

template<>
double box2d::round ( double  value,
uint32_t  precision 
)
inline

◆ round() [4/7]

template<>
long double box2d::round ( long double  value,
uint32_t  precision 
)
inline

◆ round() [5/7]

template<>
Fixed32 box2d::round ( Fixed32  value,
uint32_t  precision 
)
inline

◆ round() [6/7]

template<>
Fixed64 box2d::round ( Fixed64  value,
uint32_t  precision 
)
inline

◆ round() [7/7]

template<>
Vec2 box2d::round ( Vec2  value,
std::uint32_t  precision 
)
inline

◆ SetAngularVelocity()

void box2d::SetAngularVelocity ( Body body,
AngularVelocity  omega 
)
inlinenoexcept

Sets the angular velocity.

Parameters
bodyBody to set the angular velocity of.
omegathe new angular velocity in radians/second.

◆ SetAsBox()

void box2d::SetAsBox ( PolygonShape shape,
Length  hx,
Length  hy,
const Length2D  center,
Angle  angle 
)
noexcept

Build vertices to represent an oriented box.

Parameters
shapeShape to set as a box.
hxthe half-width.
hythe half-height.
centerthe center of the box in local coordinates.
anglethe rotation of the box in local coordinates.

◆ SetAwake() [1/3]

void box2d::SetAwake ( Joint j)
noexcept

◆ SetAwake() [2/3]

void box2d::SetAwake ( Fixture f)
noexcept

Sets the associated body's sleep status to awake.

Note
This is a convenience function that simply looks up the fixture's body and calls that body' SetAwake method.
Parameters
fFixture whose body should be awoken.

◆ SetAwake() [3/3]

void box2d::SetAwake ( Contact c)
noexcept

◆ SetForce()

void box2d::SetForce ( Body body,
const Force2D  force,
const Length2D  point 
)
inlinenoexcept

◆ SetLinearVelocity()

void box2d::SetLinearVelocity ( Body body,
const LinearVelocity2D  v 
)
inlinenoexcept

Sets the linear velocity of the center of mass.

Parameters
bodyBody to set the linear velocity of.
vthe new linear velocity of the center of mass.

◆ SetNormalImpulseAtPoint()

void box2d::SetNormalImpulseAtPoint ( VelocityConstraint vc,
VelocityConstraint::size_type  index,
Momentum  value 
)
inline

◆ SetNormalImpulses()

void box2d::SetNormalImpulses ( VelocityConstraint vc,
const Momentum2D  impulses 
)
inline

◆ SetTangentImpulseAtPoint()

void box2d::SetTangentImpulseAtPoint ( VelocityConstraint vc,
VelocityConstraint::size_type  index,
Momentum  value 
)
inline

◆ SetTangentImpulses()

void box2d::SetTangentImpulses ( VelocityConstraint vc,
const Momentum2D  impulses 
)
inline

◆ SetTorque()

void box2d::SetTorque ( Body body,
const Torque  torque 
)
inlinenoexcept

◆ ShouldCollide()

bool box2d::ShouldCollide ( const Body lhs,
const Body rhs 
)
noexcept

Should collide.

Determines whether a body should possibly be able to collide with the other body.

Returns
true if either body is dynamic and no joint prevents collision, false otherwise.

◆ Solve()

constexpr Vec2 box2d::Solve ( const Mat22  mat,
const Vec2  b 
)
noexcept

Solve A * x = b, where b is a column vector. This is more efficient than computing the inverse in one-shot cases.

◆ Solve22()

constexpr Vec2 box2d::Solve22 ( const Mat33 mat,
const Vec2  b 
)
noexcept

Solve A * x = b, where b is a column vector. This is more efficient than computing the inverse in one-shot cases. Solve only the upper 2-by-2 matrix equation.

◆ Solve33()

constexpr Vec3 box2d::Solve33 ( const Mat33 mat,
const Vec3  b 
)
noexcept

Solve A * x = b, where b is a column vector. This is more efficient than computing the inverse in one-shot cases.

◆ SolvePositionConstraint()

PositionSolution box2d::SolvePositionConstraint ( const PositionConstraint pc,
const bool  moveA,
const bool  moveB,
ConstraintSolverConf  conf 
)

Solves the given position constraint.

This pushes apart the two given positions for every point in the contact position constraint and returns the minimum separation value from the position solver manifold for each point.

See also
http://allenchou.net/2013/12/game-physics-resolution-contact-constraints/
Returns
Minimum separation distance of the position constraint's manifold points (prior to "solving").

◆ SolvePositionConstraints() [1/2]

Length box2d::SolvePositionConstraints ( Span< PositionConstraint positionConstraints,
ConstraintSolverConf  conf = GetDefaultPositionSolverConf() 
)

Solves the given position constraints.

This updates positions (and nothing else) by calling the position constraint solving function.

Note
Can't expect the returned minimum separation to be greater than or equal to -conf.linearSlop because code won't push the separation above this amount to begin with.
Returns
Minimum separation.
See also
MinSeparationThreshold.
Solve.

◆ SolvePositionConstraints() [2/2]

Length box2d::SolvePositionConstraints ( Span< PositionConstraint positionConstraints,
const BodyConstraint bodiesA,
const BodyConstraint bodiesB,
ConstraintSolverConf  conf = GetDefaultToiPositionSolverConf() 
)

Solves the given position constraints.

This updates positions (and nothing else) for the two bodies identified by the given indexes by calling the position constraint solving function.

Note
Can't expect the returned minimum separation to be greater than or equal to ConstraintSolverConf.max_separation because code won't push the separation above this amount to begin with.
Parameters
positionConstraintsPositions constraints.
bodiesAPointer to body constraint for body A.
bodiesBPointer to body constraint for body B.
confConfiguration for solving the constraint.
Returns
Minimum separation (which is the same as the max amount of penetration/overlap).

◆ SolveVelocityConstraint()

Momentum box2d::SolveVelocityConstraint ( VelocityConstraint vc)

Solves the velocity constraint.

This updates the tangent and normal impulses of the velocity constraint points of the given velocity constraint and updates the given velocities.

Warning
Behavior is undefined unless the velocity constraint point count is 1 or 2.
Note
Linear velocity is only changed if the inverse mass of either body is non-zero.
Angular velocity is only changed if the inverse rotational inertia of either body is non-zero.
Precondition
The velocity constraint must have a valid normal, a valid tangent, valid point relative positions, and valid velocity biases.

◆ Sqrt()

template<typename T >
auto box2d::Sqrt ( t)
inline

◆ Square()

template<class TYPE >
constexpr auto box2d::Square ( TYPE  t)
inlinenoexcept

◆ Step()

StepStats box2d::Step ( World world,
Time  timeStep,
World::ts_iters_type  velocityIterations = 8,
World::ts_iters_type  positionIterations = 3 
)

Steps the world ahead by a given time amount.

Performs position and velocity updating, sleeping of non-moving bodies, updating of the contacts, and notifying the contact listener of begin-contact, end-contact, pre-solve, and post-solve events. If the given velocity and position iterations are more than zero, this method also respectively performs velocity and position resolution of the contacting bodies.

Note
While body velocities are updated accordingly (per the sum of forces acting on them), body positions (barring any collisions) are updated as if they had moved the entire time step at those resulting velocities. In other words, a body initially at p0 going v0 fast with a sum acceleration of a, after time t and barring any collisions, will have a new velocity (v1) of v0 + (a * t) and a new position (p1) of p0 + v1 * t.
Warning
Varying the time step may lead to non-physical behaviors.
Postcondition
Static bodies are unmoved.
Kinetic bodies are moved based on their previous velocities.
Dynamic bodies are moved based on their previous velocities, gravity, applied forces, applied impulses, masses, damping, and the restitution and friction values of their fixtures when they experience collisions.
Parameters
worldWorld to step.
timeStepAmount of time to simulate (in seconds). This should not vary.
velocityIterationsNumber of iterations for the velocity constraint solver.
positionIterationsNumber of iterations for the position constraint solver. The position constraint solver resolves the positions of bodies that overlap.

◆ StripUnit()

constexpr RealNum box2d::StripUnit ( const RealNum  value)
inline

◆ StripUnits()

constexpr Vec2 box2d::StripUnits ( const Vector2D< RealNum value)
inline

◆ Swap()

template<typename T >
constexpr void box2d::Swap ( T &  a,
T &  b 
)
inline

◆ TestOverlap() [1/3]

bool box2d::TestOverlap ( const Shape shapeA,
child_count_t  indexA,
const Transformation xfA,
const Shape shapeB,
child_count_t  indexB,
const Transformation xfB 
)

Determine if two generic shapes overlap.

◆ TestOverlap() [2/3]

constexpr bool box2d::TestOverlap ( const AABB  a,
const AABB  b 
)
noexcept

◆ TestOverlap() [3/3]

bool box2d::TestOverlap ( const BroadPhase bp,
BroadPhase::size_type  proxyIdA,
BroadPhase::size_type  proxyIdB 
)
inline

◆ TestPoint()

bool box2d::TestPoint ( const Fixture f,
const Length2D  p 
)
noexcept

Test a point for containment in a fixture.

Parameters
fFixture to use for test.
pPoint in world coordinates.

◆ Transform() [1/5]

PolygonShape box2d::Transform ( PolygonShape  value,
Transformation  xfm 
)
inlinenoexcept

◆ Transform() [2/5]

constexpr Vec2 box2d::Transform ( const Vec2  v,
const Mat22 A 
)
inlinenoexcept

Multiply a matrix times a vector. If a rotation matrix is provided, then this transforms the vector from one frame to another.

◆ Transform() [3/5]

constexpr Vec3 box2d::Transform ( const Vec3 v,
const Mat33 A 
)
inlinenoexcept

Multiply a matrix times a vector.

◆ Transform() [4/5]

constexpr Vec2 box2d::Transform ( const Vec2  v,
const Mat33 A 
)
inlinenoexcept

Multiply a matrix times a vector.

◆ Transform() [5/5]

constexpr Length2D box2d::Transform ( const Length2D  v,
const Transformation  T 
)
inlinenoexcept

Transforms the given 2-D vector with the given transformation.

Rotate and translate the given 2-D linear position according to the rotation and translation defined by the given transformation.

Note
Passing the output of this function to InverseTransform (with the same transformation again) will result in the original vector being returned.
For a 2-D linear position of the origin (0, 0), the result is simply the translation.
See also
InverseTransform.
Parameters
v2-D position to transform (to rotate and then translate).
TTransformation (a translation and rotation) to apply to the given vector.
Returns
Rotated and translated vector.

◆ Unawaken()

bool box2d::Unawaken ( Body body)
inlinenoexcept

Puts the body to sleep if it's awake.

◆ Validate()

bool box2d::Validate ( const PolygonShape shape)

Validate convexity of the given shape.

Note
This is a time consuming operation.
Returns
true if valid

Variable Documentation

◆ BuiltVersion

constexpr auto box2d::BuiltVersion = Version{3, 0, 0}

◆ DefaultAabbExtension

constexpr auto box2d::DefaultAabbExtension = DefaultLinearSlop * RealNum{20}

◆ DefaultAngularSleepTolerance

constexpr auto box2d::DefaultAngularSleepTolerance = RealNum{(Pi * 2) / 180} * RadianPerSecond

Default angular sleep tolerance.

A body cannot sleep if its angular velocity is above this amount.

◆ DefaultAngularSlop

constexpr auto box2d::DefaultAngularSlop = (Pi * RealNum{2} * Radian) / RealNum{180}

Default angular slop.

A small angle used as a collision and constraint tolerance. Usually it is chosen to be numerically significant, but visually insignificant.

◆ DefaultDistanceMultiplier

constexpr auto box2d::DefaultDistanceMultiplier = RealNum{2}

◆ DefaultLinearSleepTolerance

constexpr auto box2d::DefaultLinearSleepTolerance = RealNum{0.01f} * MeterPerSecond

Default linear sleep tolerance.

A body cannot sleep if the magnitude of its linear velocity is above this amount.

◆ DefaultLinearSlop

constexpr auto box2d::DefaultLinearSlop = Length{Meter / RealNum{1000}}

Default linear slop.

Length used as a collision and constraint tolerance. Usually chosen to be numerically significant, but visually insignificant. Lower or raise to decrease or increase respectively the minimum of space between bodies at rest.

Note
Smaller values relative to sizes of bodies increases the time it takes for bodies to come to rest.

◆ DefaultMaxAngularCorrection

constexpr auto box2d::DefaultMaxAngularCorrection = DefaultAngularSlop * RealNum{4}

Default maximum angular correction.

Note
This value should be greater than the angular slop value.

◆ DefaultMaxDistanceIters

constexpr auto box2d::DefaultMaxDistanceIters = std::uint8_t{20}

Default max number of distance iterations.

◆ DefaultMaxLinearCorrection

constexpr auto box2d::DefaultMaxLinearCorrection = DefaultLinearSlop * RealNum{40}

Default maximum linear correction.

The maximum linear position correction used when solving constraints. This helps to prevent overshoot.

Note
This value should be greater than the linear slop value.

◆ DefaultMaxSubSteps

constexpr auto box2d::DefaultMaxSubSteps = std::uint8_t{48}

Default maximum number of sub steps.

This is the default maximum number of sub-steps per contact in continuous physics simulation. In other words, this is the default maximum number of times in a world step that a contact will have continuous collision resolution done for it.

Note
Used in the TOI phase of step processing.

◆ DefaultMaxToiIters

constexpr auto box2d::DefaultMaxToiIters = std::uint8_t{20}

Default maximum time of impact iterations.

◆ DefaultMaxToiRootIters

constexpr auto box2d::DefaultMaxToiRootIters = std::uint8_t{30}

Default maximum time of impact root iterator count.

◆ DefaultMinStillTimeToSleep

constexpr auto box2d::DefaultMinStillTimeToSleep = Time{Second / RealNum{2}}

Default minimum still time to sleep.

The default minimum time bodies must be still for bodies to be put to sleep.

◆ DefaultStepFrequency

constexpr auto box2d::DefaultStepFrequency = Frequency{Hertz * RealNum{60}}

◆ DefaultStepTime

constexpr auto box2d::DefaultStepTime = Time{Second / RealNum{60}}

◆ DefaultVelocityThreshold

constexpr auto box2d::DefaultVelocityThreshold = (RealNum{8} / RealNum{10}) * MeterPerSecond

Default velocity threshold.

◆ Degree

constexpr auto box2d::Degree = Pi / RealNum{180}

◆ EarthlyGravity

constexpr auto box2d::EarthlyGravity = LinearAcceleration2D{RealNum{0} * MeterPerSquareSecond, RealNum{-9.8f} * MeterPerSquareSecond}

Earthly gravity.

An approximation of Earth's average gravity at sea-level.

◆ Hertz

constexpr auto box2d::Hertz = RealNum{1}

◆ Kilogram

constexpr auto box2d::Kilogram = RealNum{1}

◆ KilogramPerSquareMeter

constexpr auto box2d::KilogramPerSquareMeter = RealNum{1}

◆ Mat22_identity

constexpr auto box2d::Mat22_identity = Mat22(Vec2{1, 0}, Vec2{0, 1})

Identity value for Mat22 objects.

See also
Mat22.

◆ Mat22_zero

constexpr auto box2d::Mat22_zero = Mat22(Vec2_zero, Vec2_zero)

An all zero Mat22 value.

See also
Mat22.

◆ Mat33_zero

constexpr auto box2d::Mat33_zero = Mat33(Vec3_zero, Vec3_zero, Vec3_zero)

◆ MaxBodies

constexpr auto box2d::MaxBodies
Initial value:
= static_cast<std::uint16_t>(std::numeric_limits<std::uint16_t>::max() -
std::uint16_t{1})

Maximum number of bodies in a world (65534 based off uint16_t and eliminating one value for invalid).

◆ MaxContacts

constexpr auto box2d::MaxContacts = contact_count_t{MaxBodies} * contact_count_t{MaxBodies - 1} / contact_count_t{2}

Maximum number of contacts in a world (2147319811).

Uses the formula for the maximum number of edges in an undirectional graph of MaxBodies nodes. This occurs when every possible body is connected to every other body.

◆ MaxFloat

constexpr auto box2d::MaxFloat = std::numeric_limits<RealNum>::max()

◆ MaxJoints

constexpr auto box2d::MaxJoints
Initial value:
= static_cast<std::uint16_t>(std::numeric_limits<std::uint16_t>::max() -
std::uint16_t{1})

Maximum number of joints in a world (65534 based off std::uint16_t and eliminating one value for invalid).

◆ MaxManifoldPoints

constexpr auto box2d::MaxManifoldPoints = std::uint8_t{2}

Maximum manifold points. This is the maximum number of contact points between two convex shapes. Do not change this value.

Note
For memory efficiency, uses the smallest integral type that can hold the value.

◆ MaxShapeVertices

constexpr auto box2d::MaxShapeVertices = std::uint8_t{254}

Maximum number of vertices for any shape type.

Note
For memory efficiency, uses the smallest integral type that can hold the value.

◆ Meter

constexpr auto box2d::Meter = RealNum{1}

◆ MeterPerSecond

constexpr auto box2d::MeterPerSecond = RealNum{1}

◆ MeterPerSquareSecond

constexpr auto box2d::MeterPerSquareSecond = RealNum{1}

◆ Newton

constexpr auto box2d::Newton = RealNum{1}

◆ NewtonMeter

constexpr auto box2d::NewtonMeter = RealNum{1}

◆ NewtonSecond

constexpr auto box2d::NewtonSecond = RealNum{1}

◆ Pi

constexpr auto box2d::Pi = RealNum(3.14159265358979323846264338327950288)

Pi.

While the include file definition of M_PI may be a POSIX compliance requirement and initially attractive to use, it's apparently not a C++ standards requirement and casually including it pollutes the namespace of all code that uses this library. Whatever the case, MSVS2017 doesn't make it part of the cmath include without enabling _USE_MATH_DEFINES. So rather than add yet more C-preprocessor macros to all sources that this library may be compiled with, it's simply hard-coded in here instead using a C++ mechanism that also keeps it with the enclosing namespace.

Note
Any narrowing is intentional.

◆ Radian

constexpr auto box2d::Radian = RealNum{1}

◆ RadianPerSecond

constexpr auto box2d::RadianPerSecond = RealNum{1}

◆ RadianPerSquareSecond

constexpr auto box2d::RadianPerSquareSecond = RealNum{1}

◆ Second

constexpr auto box2d::Second = RealNum{1}

◆ SquareMeter

constexpr auto box2d::SquareMeter = RealNum{1}

◆ SquareRadian

constexpr auto box2d::SquareRadian = Radian * Radian

◆ Transform_identity

constexpr auto box2d::Transform_identity = Transformation{Vec2_zero * Meter, UnitVec2::GetRight()}

◆ Vec2_zero

constexpr auto box2d::Vec2_zero = Vec2{0, 0}

An all zero Vec2 value.

See also
Vec2.

◆ Vec3_zero

constexpr auto box2d::Vec3_zero = Vec3{0, 0, 0}

An all zero Vec3 value.

See also
Vec3.