PlayRho  1.1.0
An Interactive Real-Time-Oriented C++ Physics Engine & Library
playrho::d2::World Class Reference

Definition of an independent and simulatable "world". More...

#include <World.hpp>

Collaboration diagram for playrho::d2::World:
[legend]

Public Types

using Bodies = std::vector< BodyID >
 Bodies container type.
 
using Contacts = std::vector< KeyedContactPtr >
 Container type for keyed contact identifiers.
 
using Joints = std::vector< JointID >
 Container type for joint identifiers.
 
using BodyJoints = std::vector< std::pair< BodyID, JointID > >
 Container type for body associated joint identifiers.
 
using Fixtures = std::vector< FixtureID >
 Container type for fixture identifiers.
 
using FixtureListener = std::function< void(FixtureID)>
 Listener type for some fixture related events.
 
using JointListener = std::function< void(JointID)>
 Listener type for some joint related events.
 
using ContactListener = std::function< void(ContactID)>
 Listener type for some contact related events.
 
using ManifoldContactListener = std::function< void(ContactID, const Manifold &)>
 Listener type for some manifold contact events.
 
using ImpulsesContactListener = std::function< void(ContactID, const ContactImpulsesList &, unsigned)>
 Impulses contact listener.
 

Public Member Functions

Special Member Functions

Special member functions that are explicitly defined.

 World (const WorldConf &def=GetDefaultWorldConf())
 Constructs a world object. More...
 
 World (const World &other)
 Copy constructor. More...
 
Worldoperator= (const World &other)
 Assignment operator. More...
 
 ~World () noexcept
 Destructor. More...
 
Listener Member Functions
void SetFixtureDestructionListener (const FixtureListener &listener) noexcept
 Registers a destruction listener for fixtures.
 
void SetJointDestructionListener (const JointListener &listener) noexcept
 Registers a destruction listener for joints.
 
void SetBeginContactListener (ContactListener listener) noexcept
 Registers a begin contact event listener.
 
void SetEndContactListener (ContactListener listener) noexcept
 Registers an end contact event listener.
 
void SetPreSolveContactListener (ManifoldContactListener listener) noexcept
 Registers a pre-solve contact event listener.
 
void SetPostSolveContactListener (ImpulsesContactListener listener) noexcept
 Registers a post-solve contact event listener.
 
Miscellaneous Member Functions
void Clear () noexcept
 Clears this world. More...
 
StepStats Step (const StepConf &conf=StepConf{})
 Steps the world simulation according to the given configuration. More...
 
bool IsStepComplete () const noexcept
 Whether or not "step" is complete. More...
 
bool GetSubStepping () const noexcept
 Gets whether or not sub-stepping is enabled. More...
 
void SetSubStepping (bool flag) noexcept
 Enables/disables single stepped continuous physics. More...
 
const DynamicTreeGetTree () const noexcept
 Gets access to the broad-phase dynamic tree information.
 
bool IsLocked () const noexcept
 Is the world locked (in the middle of a time step).
 
void ShiftOrigin (Length2 newOrigin)
 Shifts the world origin. More...
 
Length GetMinVertexRadius () const noexcept
 Gets the minimum vertex radius that shapes in this world can be. More...
 
Length GetMaxVertexRadius () const noexcept
 Gets the maximum vertex radius that shapes in this world can be. More...
 
Frequency GetInvDeltaTime () const noexcept
 Gets the inverse delta time. More...
 
Body Member Functions.

Member functions relating to bodies.

BodyCounter GetBodyRange () const noexcept
 Gets the extent of the currently valid body range. More...
 
SizedRange< Bodies::const_iterator > GetBodies () const noexcept
 Gets the world body range for this constant world. More...
 
SizedRange< Bodies::const_iterator > GetBodiesForProxies () const noexcept
 Gets the bodies-for-proxies range for this world. More...
 
BodyID CreateBody (const BodyConf &def=GetDefaultBodyConf())
 Creates a rigid body with the given configuration. More...
 
const BodyGetBody (BodyID id) const
 Gets the state of the identified body. More...
 
void SetBody (BodyID id, const Body &value)
 Sets the state of the identified body. More...
 
void Destroy (BodyID id)
 Destroys the identified body. More...
 
SizedRange< Fixtures::const_iterator > GetFixtures (BodyID id) const
 Gets the range of fixtures attached to the identified body. More...
 
SizedRange< World::BodyJoints::const_iterator > GetJoints (BodyID id) const
 Gets the range of joints attached to the identified body. More...
 
SizedRange< World::Contacts::const_iterator > GetContacts (BodyID id) const
 Gets the container of contacts attached to the identified body. More...
 
Fixture Member Functions

Member functions relating to fixtures.

FixtureCounter GetFixtureRange () const noexcept
 Gets the extent of the currently valid fixture range. More...
 
FixtureID CreateFixture (const FixtureConf &def=FixtureConf{})
 Creates a fixture and attaches it to the identified body. More...
 
const FixtureConfGetFixture (FixtureID id) const
 Gets the identified fixture state. More...
 
void SetFixture (FixtureID id, const FixtureConf &value)
 Sets the identified fixture's state. More...
 
bool Destroy (FixtureID id)
 Destroys the identified fixture. More...
 
Joint Member Functions

Member functions relating to joints.

JointCounter GetJointRange () const noexcept
 Gets the extent of the currently valid joint range. More...
 
SizedRange< Joints::const_iterator > GetJoints () const noexcept
 Gets the world joint range. More...
 
JointID CreateJoint (const Joint &def)
 Creates a joint to constrain one or more bodies. More...
 
const JointGetJoint (JointID id) const
 Gets the value of the identified joint. More...
 
void SetJoint (JointID id, const Joint &def)
 Sets the identified joint to the given value. More...
 
void Destroy (JointID id)
 Destroys the identified joint. More...
 
Contact Member Functions

Member functions relating to contacts.

ContactCounter GetContactRange () const noexcept
 Gets the extent of the currently valid contact range. More...
 
SizedRange< Contacts::const_iterator > GetContacts () const noexcept
 Gets the world contact range. More...
 
const ContactGetContact (ContactID id) const
 Gets the identified contact. More...
 
void SetContact (ContactID id, const Contact &value)
 Sets the identified contact's state. More...
 
const ManifoldGetManifold (ContactID id) const
 Gets the collision manifold for the identified contact. More...
 

Private Attributes

propagate_const< std::unique_ptr< WorldImpl > > m_impl
 Pointer to implementation (PIMPL) More...
 

Related Functions

(Note that these are not member functions.)

AABB ComputeAABB (const World &world, FixtureID id)
 Computes the AABB for the identified fixture within the given world.
 
AABB ComputeAABB (const World &world, BodyID id)
 Computes the AABB for the identified body within the given world.
 
bool RayCast (const World &world, const RayCastInput &input, const FixtureRayCastCB &callback)
 Ray-cast the world for all fixtures in the path of the ray. More...
 
DistanceJointConf GetDistanceJointConf (const World &world, BodyID bodyA, BodyID bodyB, Length2 anchorA=Length2{}, Length2 anchorB=Length2{})
 Gets the configuration for the given parameters.
 
FrictionJointConf GetFrictionJointConf (const World &world, BodyID bodyA, BodyID bodyB, Length2 anchor)
 Gets the confguration for the given parameters.
 
GearJointConf GetGearJointConf (const World &world, JointID id1, JointID id2, Real ratio=Real{1})
 Gets the configuration for the given parameters.
 
MotorJointConf GetMotorJointConf (const World &world, BodyID bA, BodyID bB)
 Gets the confguration for the given parameters.
 
PrismaticJointConf GetPrismaticJointConf (const World &world, BodyID bA, BodyID bB, const Length2 anchor, const UnitVec axis)
 Gets the configuration for the given parameters.
 
LinearVelocity GetLinearVelocity (const World &world, const PrismaticJointConf &joint) noexcept
 Gets the current linear velocity of the given configuration.
 
PulleyJointConf GetPulleyJointConf (const World &world, BodyID bA, BodyID bB, Length2 groundA, Length2 groundB, Length2 anchorA, Length2 anchorB)
 Gets the configuration for the given parameters.
 
RevoluteJointConf GetRevoluteJointConf (const World &world, BodyID bodyA, BodyID bodyB, Length2 anchor)
 Gets the configuration for the given parameters.
 
Angle GetAngle (const World &world, const RevoluteJointConf &conf)
 Gets the current angle of the given configuration in the given world.
 
AngularVelocity GetAngularVelocity (const World &world, const RevoluteJointConf &conf)
 Gets the current angular velocity of the given configuration.
 
WeldJointConf GetWeldJointConf (const World &world, BodyID bodyA, BodyID bodyB, const Length2 anchor=Length2{})
 Gets the configuration for the given parameters.
 
WheelJointConf GetWheelJointConf (const World &world, BodyID bodyA, BodyID bodyB, Length2 anchor, UnitVec axis=UnitVec::GetRight())
 Gets the definition data for the given parameters.
 
AngularVelocity GetAngularVelocity (const World &world, const WheelJointConf &conf)
 Gets the angular velocity for the given configuration within the specified world.
 
BodyCounter GetBodyRange (const World &world) noexcept
 Gets the extent of the currently valid body range. More...
 
SizedRange< std::vector< BodyID >::const_iterator > GetBodies (const World &world) noexcept
 Gets the bodies of the specified world.
 
SizedRange< std::vector< BodyID >::const_iterator > GetBodiesForProxies (const World &world) noexcept
 Gets the bodies-for-proxies range for the given world.
 
BodyID CreateBody (World &world, const BodyConf &def=GetDefaultBodyConf())
 Creates a rigid body with the given configuration. More...
 
const BodyGetBody (const World &world, BodyID id)
 Gets the body configuration for the identified body. More...
 
void SetBody (World &world, BodyID id, const Body &body)
 Sets the body state for the identified body. More...
 
void Destroy (World &world, BodyID id)
 Destroys the identified body. More...
 
SizedRange< std::vector< FixtureID >::const_iterator > GetFixtures (const World &world, BodyID id)
 Gets the range of all constant fixtures attached to the given body. More...
 
FixtureCounter GetFixtureCount (const World &world, BodyID id)
 Gets the count of fixtures associated with the identified body. More...
 
LinearAcceleration2 GetLinearAcceleration (const World &world, BodyID id)
 Gets this body's linear acceleration. More...
 
AngularAcceleration GetAngularAcceleration (const World &world, BodyID id)
 Gets this body's angular acceleration. More...
 
Acceleration GetAcceleration (const World &world, BodyID id)
 Gets the acceleration of the identified body. More...
 
void SetAcceleration (World &world, BodyID id, LinearAcceleration2 linear, AngularAcceleration angular)
 Sets the linear and rotational accelerations on the body. More...
 
void SetAcceleration (World &world, BodyID id, LinearAcceleration2 value)
 Sets the linear accelerations on the body. More...
 
void SetAcceleration (World &world, BodyID id, AngularAcceleration value)
 Sets the rotational accelerations on the body. More...
 
void SetAcceleration (World &world, BodyID id, Acceleration value)
 Sets the accelerations on the given body. More...
 
void SetTransformation (World &world, BodyID id, Transformation xfm)
 Sets the transformation of the body. More...
 
void SetTransform (World &world, BodyID id, Length2 location, Angle angle)
 Sets the position of the body's origin and rotation. More...
 
void SetLocation (World &world, BodyID id, Length2 value)
 Sets the body's location. More...
 
void SetAngle (World &world, BodyID id, Angle value)
 Sets the body's angular orientation. More...
 
void RotateAboutWorldPoint (World &world, BodyID id, Angle amount, Length2 worldPoint)
 Rotates a body a given amount around a point in world coordinates. More...
 
void RotateAboutLocalPoint (World &world, BodyID id, Angle amount, Length2 localPoint)
 Rotates a body a given amount around a point in body local coordinates. More...
 
Acceleration CalcGravitationalAcceleration (const World &world, BodyID id)
 Calculates the gravitationally associated acceleration for the given body within its world. More...
 
BodyCounter GetWorldIndex (const World &world, const BodyID id) noexcept
 Gets the world index for the given body. More...
 
BodyType GetType (const World &world, BodyID id)
 Gets the type of the identified body. More...
 
void SetType (World &world, BodyID id, BodyType value, bool resetMassData=true)
 Sets the type of the given body. More...
 
Transformation GetTransformation (const World &world, BodyID id)
 Gets the body's transformation. More...
 
Length2 GetLocation (const World &world, BodyID id)
 Convenience function for getting just the location of the identified body. More...
 
Length2 GetWorldPoint (const World &world, BodyID id, const Length2 localPoint)
 Gets the world coordinates of a point given in coordinates relative to the body's origin. More...
 
UnitVec GetLocalVector (const World &world, BodyID body, const UnitVec uv)
 Convenience function for getting the local vector of the identified body. More...
 
Length2 GetLocalPoint (const World &world, BodyID body, const Length2 worldPoint)
 Gets a local point relative to the body's origin given a world point. More...
 
Angle GetAngle (const World &world, BodyID id)
 Gets the angle of the identified body. More...
 
UnitVec GetWorldVector (const World &world, BodyID body, UnitVec localVector)
 Convenience function for getting a world vector of the identified body.
 
Velocity GetVelocity (const World &world, BodyID id)
 Gets the velocity of the identified body. More...
 
void SetVelocity (World &world, BodyID id, const Velocity &value)
 Sets the body's velocity (linear and angular velocity). More...
 
bool IsAwake (const World &world, BodyID id)
 Gets the awake/asleep state of this body. More...
 
void SetAwake (World &world, BodyID id)
 Wakes up the identified body. More...
 
void UnsetAwake (World &world, BodyID id)
 Sleeps the identified body. More...
 
LinearVelocity2 GetLinearVelocity (const World &world, BodyID id)
 Gets the linear velocity of the center of mass of the identified body. More...
 
AngularVelocity GetAngularVelocity (const World &world, BodyID id)
 Gets the angular velocity. More...
 
void SetVelocity (World &world, BodyID id, const Velocity &value)
 Sets the body's velocity (linear and angular velocity). More...
 
void SetVelocity (World &world, BodyID id, const LinearVelocity2 &value)
 Sets the velocity of the identified body. More...
 
void SetVelocity (World &world, BodyID id, AngularVelocity value)
 Sets the velocity of the identified body. More...
 
void DestroyFixtures (World &world, BodyID id, bool resetMassData=true)
 Destroys fixtures of the identified body. More...
 
bool IsEnabled (const World &world, BodyID id)
 Gets the enabled/disabled state of the body. More...
 
void SetEnabled (World &world, BodyID id, bool value)
 Sets the enabled state of the body. More...
 
bool IsAwake (const World &world, BodyID id)
 Gets the awake/asleep state of this body. More...
 
void SetAwake (World &world, BodyID id)
 Wakes up the identified body. More...
 
void UnsetAwake (World &world, BodyID id)
 Sleeps the identified body. More...
 
bool Awaken (World &world, BodyID id)
 Awakens the body if it's asleep. More...
 
bool IsMassDataDirty (const World &world, BodyID id)
 Gets whether the body's mass-data is dirty. More...
 
bool IsFixedRotation (const World &world, BodyID id)
 Gets whether the body has fixed rotation. More...
 
void SetFixedRotation (World &world, BodyID id, bool value)
 Sets this body to have fixed rotation. More...
 
Length2 GetWorldCenter (const World &world, BodyID id)
 Get the world position of the center of mass of the specified body. More...
 
InvMass GetInvMass (const World &world, BodyID id)
 Gets the inverse total mass of the body. More...
 
InvRotInertia GetInvRotInertia (const World &world, BodyID id)
 Gets the inverse rotational inertia of the body. More...
 
Mass GetMass (const World &world, BodyID id)
 Gets the mass of the body. More...
 
RotInertia GetRotInertia (const World &world, BodyID id)
 Gets the rotational inertia of the body. More...
 
Length2 GetLocalCenter (const World &world, BodyID id)
 Gets the local position of the center of mass of the specified body. More...
 
RotInertia GetLocalRotInertia (const World &world, BodyID id)
 Gets the rotational inertia of the body about the local origin. More...
 
MassData GetMassData (const World &world, BodyID id)
 Gets the mass data of the body. More...
 
MassData ComputeMassData (const World &world, BodyID id)
 Computes the identified body's mass data. More...
 
void SetMassData (World &world, BodyID id, const MassData &massData)
 Sets the mass properties to override the mass properties of the fixtures. More...
 
void ResetMassData (World &world, BodyID id)
 Resets the mass data properties. More...
 
SizedRange< std::vector< std::pair< BodyID, JointID > >::const_iterator > GetJoints (const World &world, BodyID id)
 Gets the range of all joints attached to the identified body. More...
 
bool IsSpeedable (const World &world, BodyID id)
 Is identified body "speedable". More...
 
bool IsAccelerable (const World &world, BodyID id)
 Is identified body "accelerable"? More...
 
bool IsImpenetrable (const World &world, BodyID id)
 Is the body treated like a bullet for continuous collision detection? More...
 
void SetImpenetrable (World &world, BodyID id)
 Sets the impenetrable status of the identified body. More...
 
void UnsetImpenetrable (World &world, BodyID id)
 Unsets the impenetrable status of the identified body. More...
 
void SetImpenetrable (World &world, BodyID id, bool value)
 Convenience function that sets/unsets the impenetrable status of the identified body. More...
 
bool IsSleepingAllowed (const World &world, BodyID id)
 Gets whether the identified body is allowed to sleep. More...
 
void SetSleepingAllowed (World &world, BodyID, bool value)
 Sets whether the identified body is allowed to sleep. More...
 
SizedRange< std::vector< KeyedContactPtr >::const_iterator > GetContacts (const World &world, BodyID id)
 Gets the container of all contacts attached to the identified body. More...
 
Force2 GetCentripetalForce (const World &world, BodyID id, Length2 axis)
 Gets the centripetal force necessary to put the body into an orbit having the given radius. More...
 
void ApplyForceToCenter (World &world, BodyID id, Force2 force)
 Applies a force to the center of mass of the given body. More...
 
void ApplyForce (World &world, BodyID id, Force2 force, Length2 point)
 Apply a force at a world point. More...
 
void ApplyTorque (World &world, BodyID id, Torque torque)
 Applies a torque. More...
 
void ApplyLinearImpulse (World &world, BodyID id, Momentum2 impulse, Length2 point)
 Applies an impulse at a point. More...
 
void ApplyAngularImpulse (World &world, BodyID id, AngularMomentum impulse)
 Applies an angular impulse. More...
 
void SetForce (World &world, BodyID id, Force2 force, Length2 point) noexcept
 Sets the given amount of force at the given point to the given body. More...
 
void SetTorque (World &world, BodyID id, Torque torque) noexcept
 Sets the given amount of torque to the given body. More...
 
Frequency GetLinearDamping (const World &world, BodyID id)
 Gets the linear damping of the body. More...
 
void SetLinearDamping (World &world, BodyID id, NonNegative< Frequency > linearDamping)
 Sets the linear damping of the body. More...
 
Frequency GetAngularDamping (const World &world, BodyID id)
 Gets the angular damping of the body. More...
 
void SetAngularDamping (World &world, BodyID id, NonNegative< Frequency > angularDamping)
 Sets the angular damping of the body. More...
 
BodyCounter GetAwakeCount (const World &world) noexcept
 Gets the count of awake bodies in the given world.
 
BodyCounter Awaken (World &world) noexcept
 Awakens all of the bodies in the given world. More...
 
BodyID FindClosestBody (const World &world, Length2 location) noexcept
 Finds body in given world that's closest to the given location.
 
BodyCounter GetBodyCount (const World &world) noexcept
 Gets the body count in the given world. More...
 
void SetAccelerations (World &world, Acceleration acceleration) noexcept
 Sets the accelerations of all the world's bodies to the given value.
 
void SetAccelerations (World &world, LinearAcceleration2 acceleration) noexcept
 Sets the accelerations of all the world's bodies to the given value. More...
 
void ClearForces (World &world) noexcept
 Clears forces. More...
 
template<class F >
void SetAccelerations (World &world, F fn)
 Sets the accelerations of all the world's bodies. More...
 
ContactCounter GetContactRange (const World &world) noexcept
 Gets the extent of the currently valid contact range. More...
 
SizedRange< std::vector< KeyedContactPtr >::const_iterator > GetContacts (const World &world) noexcept
 Gets the contacts recognized within the given world.
 
const ContactGetContact (const World &world, ContactID id)
 Gets the identified contact. More...
 
void SetContact (World &world, ContactID id, const Contact &value)
 Sets the identified contact's state. More...
 
bool IsTouching (const World &world, ContactID id)
 Is this contact touching? More...
 
bool IsAwake (const World &world, ContactID id)
 Gets the awake status of the specified contact. More...
 
void SetAwake (World &world, ContactID id)
 Sets awake the bodies of the fixtures of the given contact. More...
 
BodyID GetBodyA (const World &world, ContactID id)
 Gets the body-A of the identified contact if it has one. More...
 
BodyID GetBodyB (const World &world, ContactID id)
 Gets the body-B of the identified contact if it has one. More...
 
FixtureID GetFixtureA (const World &world, ContactID id)
 Gets fixture A of the identified contact. More...
 
FixtureID GetFixtureB (const World &world, ContactID id)
 Gets fixture B of the identified contact. More...
 
ChildCounter GetChildIndexA (const World &world, ContactID id)
 Get the child primitive index for fixture A. More...
 
ChildCounter GetChildIndexB (const World &world, ContactID id)
 Get the child primitive index for fixture B. More...
 
TimestepIters GetToiCount (const World &world, ContactID id)
 Gets the Time Of Impact (TOI) count. More...
 
bool NeedsFiltering (const World &world, ContactID id)
 Whether or not the contact needs filtering. More...
 
bool NeedsUpdating (const World &world, ContactID id)
 Whether or not the contact needs updating. More...
 
bool HasValidToi (const World &world, ContactID id)
 Whether or not the contact has a valid TOI. More...
 
Real GetToi (const World &world, ContactID id)
 Gets the time of impact (TOI) as a fraction. More...
 
Real GetDefaultFriction (const World &world, ContactID id)
 Gets the default friction amount for the identified contact. More...
 
Real GetDefaultRestitution (const World &world, ContactID id)
 Gets the default restitution amount for the identified contact. More...
 
Real GetFriction (const World &world, ContactID id)
 Gets the friction used with the identified contact. More...
 
Real GetRestitution (const World &world, ContactID id)
 Gets the restitution used with the identified contact. More...
 
void SetFriction (World &world, ContactID id, Real friction)
 Sets the friction value for the identified contact. More...
 
void SetRestitution (World &world, ContactID id, Real restitution)
 Sets the restitution value for the specified contact. More...
 
const ManifoldGetManifold (const World &world, ContactID id)
 Gets the manifold for the identified contact. More...
 
WorldManifold GetWorldManifold (const World &world, ContactID id)
 Gets the world manifold for the identified contact. More...
 
void ResetFriction (World &world, ContactID id)
 Resets the friction mixture to the default value. More...
 
void ResetRestitution (World &world, ContactID id)
 Resets the restitution to the default value. More...
 
LinearVelocity GetTangentSpeed (const World &world, ContactID id)
 Gets the tangent speed of the identified contact. More...
 
void SetTangentSpeed (World &world, ContactID id, LinearVelocity value)
 Sets the desired tangent speed for a conveyor belt behavior. More...
 
bool IsEnabled (const World &world, ContactID id)
 Gets the enabled status of the identified contact. More...
 
void SetEnabled (World &world, ContactID id)
 Sets the enabled status of the identified contact. More...
 
void UnsetEnabled (World &world, ContactID id)
 Unsets the enabled status of the identified contact. More...
 
ContactCounter GetTouchingCount (const World &world) noexcept
 Gets the touching count for the given world.
 
void SetEnabled (World &world, ContactID id, bool value)
 Convenience function for setting/unsetting the enabled status of the identified contact based on the value parameter. More...
 
ContactCounter GetContactCount (const World &world) noexcept
 Gets the count of contacts in the given world. More...
 
FixtureCounter GetFixtureRange (const World &world) noexcept
 Gets the extent of the currently valid fixture range. More...
 
FixtureCounter GetFixtureCount (const World &world) noexcept
 Gets the count of fixtures in the given world. More...
 
FixtureID CreateFixture (World &world, FixtureConf def=FixtureConf{}, bool resetMassData=true)
 Creates a fixture within the specified world. More...
 
FixtureID CreateFixture (World &world, BodyID id, const Shape &shape, FixtureConf def=FixtureConf{}, bool resetMassData=true)
 Creates a fixture within the specified world. More...
 
template<typename T >
FixtureID CreateFixture (World &world, BodyID id, const T &shapeConf, FixtureConf def=FixtureConf{}, bool resetMassData=true)
 Creates a fixture within the specified world using a configuration of a shape. More...
 
bool Destroy (World &world, FixtureID id, bool resetMassData=true)
 Destroys the identified fixture. More...
 
Filter GetFilterData (const World &world, FixtureID id)
 Gets the filter data for the identified fixture. More...
 
void SetFilterData (World &world, FixtureID id, const Filter &filter)
 Sets the contact filtering data. More...
 
BodyID GetBody (const World &world, FixtureID id)
 Gets the identifier of the body associated with the identified fixture. More...
 
Transformation GetTransformation (const World &world, FixtureID id)
 Gets the transformation associated with the given fixture. More...
 
const ShapeGetShape (const World &world, FixtureID id)
 Gets the shape associated with the identified fixture. More...
 
Real GetFriction (const World &world, FixtureID id)
 Gets the coefficient of friction of the specified fixture. More...
 
Real GetRestitution (const World &world, FixtureID id)
 Gets the coefficient of restitution of the specified fixture. More...
 
bool IsSensor (const World &world, FixtureID id)
 Is the specified fixture a sensor (non-solid)? More...
 
void SetSensor (World &world, FixtureID id, bool value)
 Sets whether the fixture is a sensor or not. More...
 
AreaDensity GetDensity (const World &world, FixtureID id)
 Gets the density of this fixture. More...
 
MassData GetMassData (const World &world, FixtureID id)
 Gets the mass data for the identified fixture in the given world. More...
 
bool TestPoint (const World &world, FixtureID id, Length2 p)
 Tests a point for containment in a fixture. More...
 
JointCounter GetJointRange (const World &world) noexcept
 Gets the extent of the currently valid joint range. More...
 
SizedRange< std::vector< JointID >::const_iterator > GetJoints (const World &world) noexcept
 Gets the joints of the specified world.
 
JointID CreateJoint (World &world, const Joint &def)
 Creates a new joint within the given world.
 
template<typename T >
JointID CreateJoint (World &world, const T &value)
 Creates a new joint from a configuration. More...
 
void Destroy (World &world, JointID id)
 Destroys the identified joint. More...
 
TypeID GetType (const World &world, JointID id)
 Gets the type of the joint. More...
 
const JointGetJoint (const World &world, JointID id)
 Gets the value of the identified joint. More...
 
void SetJoint (World &world, JointID id, const Joint &def)
 Sets the value of the identified joint. More...
 
template<typename T >
void SetJoint (World &world, JointID id, const T &value)
 Sets a joint's value from a configuration. More...
 
bool GetCollideConnected (const World &world, JointID id)
 Gets collide connected for the specified joint. More...
 
bool IsMotorEnabled (const World &world, JointID id)
 Is the joint motor enabled? More...
 
void EnableMotor (World &world, JointID id, bool value)
 Enable/disable the joint motor. More...
 
bool IsLimitEnabled (const World &world, JointID id)
 Gets whether the identified joint's limit is enabled. More...
 
void EnableLimit (World &world, JointID id, bool value)
 Sets whether the identified joint's limit is enabled or not. More...
 
BodyID GetBodyA (const World &world, JointID id)
 Gets the identifier of body-A of the identified joint. More...
 
BodyID GetBodyB (const World &world, JointID id)
 Gets the identifier of body-B of the identified joint. More...
 
Length2 GetLocalAnchorA (const World &world, JointID id)
 Get the anchor point on body-A in local coordinates. More...
 
Length2 GetLocalAnchorB (const World &world, JointID id)
 Get the anchor point on body-B in local coordinates. More...
 
Momentum2 GetLinearReaction (const World &world, JointID id)
 Gets the linear reaction on body-B at the joint anchor. More...
 
AngularMomentum GetAngularReaction (const World &world, JointID id)
 Get the angular reaction on body-B for the identified joint. More...
 
Angle GetReferenceAngle (const World &world, JointID id)
 Gets the reference-angle property of the identified joint if it has it. More...
 
UnitVec GetLocalXAxisA (const World &world, JointID id)
 Gets the local-X-axis-A property of the identified joint if it has it. More...
 
UnitVec GetLocalYAxisA (const World &world, JointID id)
 Gets the local-Y-axis-A property of the identified joint if it has it. More...
 
AngularVelocity GetMotorSpeed (const World &world, JointID id)
 Gets the motor-speed property of the identied joint if it supports it. More...
 
void SetMotorSpeed (World &world, JointID id, AngularVelocity value)
 Sets the motor-speed property of the identied joint if it supports it. More...
 
Torque GetMaxMotorTorque (const World &world, JointID id)
 Gets the max motor torque. More...
 
void SetMaxMotorTorque (World &world, JointID id, Torque value)
 Sets the maximum motor torque. More...
 
Momentum GetLinearMotorImpulse (const World &world, JointID id)
 Gets the linear motor impulse of the identified joint if it supports that. More...
 
AngularMomentum GetAngularMotorImpulse (const World &world, JointID id)
 Gets the angular motor impulse of the identified joint if it has this property. More...
 
RotInertia GetAngularMass (const World &world, JointID id)
 Gets the computed angular rotational inertia used by the joint. More...
 
Frequency GetFrequency (const World &world, JointID id)
 Gets the frequency of the identified joint if it has this property. More...
 
void SetFrequency (World &world, JointID id, Frequency value)
 Sets the frequency of the identified joint if it has this property. More...
 
AngularVelocity GetAngularVelocity (const World &world, JointID id)
 Gets the angular velocity of the identified joint if it has this property. More...
 
bool IsEnabled (const World &world, JointID id)
 Gets the enabled/disabled state of the joint. More...
 
JointCounter GetWorldIndex (const World &world, JointID id) noexcept
 Gets the world index of the given joint. More...
 
Length2 GetAnchorA (const World &world, JointID id)
 Get the anchor point on body-A in world coordinates. More...
 
Length2 GetAnchorB (const World &world, JointID id)
 Get the anchor point on body-B in world coordinates. More...
 
Real GetRatio (const World &world, JointID id)
 Gets the ratio property of the identified joint if it has it. More...
 
Length GetJointTranslation (const World &world, JointID id)
 Gets the current joint translation. More...
 
Angle GetAngle (const World &world, JointID id)
 Gets the angle property of the identified joint if it has it. More...
 
Force GetMotorForce (const World &world, JointID id, Frequency inv_dt)
 Gets the current motor force for the given joint, given the inverse time step. More...
 
Torque GetMotorTorque (const World &world, JointID id, Frequency inv_dt)
 Gets the current motor torque for the given joint given the inverse time step. More...
 
Length2 GetLinearOffset (const World &world, JointID id)
 Gets the target linear offset, in frame A. More...
 
void SetLinearOffset (World &world, JointID id, Length2 value)
 Sets the target linear offset, in frame A. More...
 
Angle GetAngularOffset (const World &world, JointID id)
 Gets the target angular offset. More...
 
void SetAngularOffset (World &world, JointID id, Angle value)
 Sets the target angular offset. More...
 
Length2 GetGroundAnchorA (const World &world, JointID id)
 Get the first ground anchor. More...
 
Length2 GetGroundAnchorB (const World &world, JointID id)
 Get the second ground anchor. More...
 
Length GetCurrentLengthA (const World &world, JointID id)
 Get the current length of the segment attached to body-A. More...
 
Length GetCurrentLengthB (const World &world, JointID id)
 Get the current length of the segment attached to body-B. More...
 
Length2 GetTarget (const World &world, JointID id)
 Gets the target point. More...
 
void SetTarget (World &world, JointID id, Length2 value)
 Sets the target point. More...
 
Angle GetAngularLowerLimit (const World &world, JointID id)
 Get the lower joint limit. More...
 
Angle GetAngularUpperLimit (const World &world, JointID id)
 Get the upper joint limit. More...
 
void SetAngularLimits (World &world, JointID id, Angle lower, Angle upper)
 Set the joint limits. More...
 
bool ShiftOrigin (World &world, JointID id, Length2 value)
 Shifts the origin of the identified joint. More...
 
Real GetDampingRatio (const World &world, JointID id)
 Gets the damping ratio associated with the identified joint if it has one. More...
 
Length GetLength (const World &world, JointID id)
 Gets the length associated with the identified joint if it has one. More...
 
LimitState GetLimitState (const World &world, JointID id)
 Gets the joint's limit state if it has one. More...
 
void SetAwake (World &world, JointID id)
 Wakes up the joined bodies. More...
 
JointCounter GetJointCount (const World &world) noexcept
 Gets the count of joints in the given world. More...
 
void SetFixtureDestructionListener (World &world, std::function< void(FixtureID)> listener) noexcept
 Sets the fixture destruction lister.
 
void SetJointDestructionListener (World &world, std::function< void(JointID)> listener) noexcept
 Sets the joint destruction lister.
 
void SetBeginContactListener (World &world, std::function< void(ContactID)> listener) noexcept
 Sets the begin-contact lister.
 
void SetEndContactListener (World &world, std::function< void(ContactID)> listener) noexcept
 Sets the end-contact lister.
 
void SetPreSolveContactListener (World &world, std::function< void(ContactID, const Manifold &)> listener) noexcept
 Sets the pre-solve-contact lister.
 
void SetPostSolveContactListener (World &world, std::function< void(ContactID, const ContactImpulsesList &, unsigned)> listener) noexcept
 Sets the post-solve-contact lister.
 
void Clear (World &world) noexcept
 Clears this world. More...
 
StepStats Step (World &world, const StepConf &conf=StepConf{})
 Steps the given world the specified amount.
 
StepStats Step (World &world, Time delta, TimestepIters velocityIterations=8, TimestepIters positionIterations=3)
 Steps the world ahead by a given time amount. More...
 
bool GetSubStepping (const World &world) noexcept
 Gets whether or not sub-stepping is enabled. More...
 
void SetSubStepping (World &world, bool flag) noexcept
 Enables/disables single stepped continuous physics. More...
 
const DynamicTreeGetTree (const World &world) noexcept
 Gets the dynamic tree of the given world.
 
FixtureCounter GetShapeCount (const World &world) noexcept
 Gets the count of unique shapes in the given world.
 
Length GetMinVertexRadius (const World &world) noexcept
 Gets the min vertex radius that shapes for the given world are allowed to be.
 
Length GetMaxVertexRadius (const World &world) noexcept
 Gets the max vertex radius that shapes for the given world are allowed to be.
 
void ShiftOrigin (World &world, Length2 newOrigin)
 Shifts the world origin. More...
 

Detailed Description

Definition of an independent and simulatable "world".

The world class manages physics entities, dynamic simulation, and queries. In a physical sense, perhaps this is more like a universe in that entities in a world have no interaction with entities in other worlds. In any case, there's precedence, from a physics-engine standpoint, for this being called a world.

Note
World instances do not themselves have any force or acceleration properties. They simply utilize the acceleration property of the bodies they manage. This is different than some other engines (like Box2D which provides a world gravity property).
World instances are composed of — i.e. contain and own — body, contact, fixture, and joint entities. These are identified by BodyID, ContactID, FixtureID, and JointID values respectively.
This class uses the pointer to implementation (PIMPL) technique and non-vitural interface (NVI) pattern to provide a complete layer of abstraction from the actual implementations used. This forms a "compilation firewall" — or application binary interface (ABI) — to help provide binary stability while facilitating experimentation and optimization.
This data structure is 8-bytes large (on at least one 64-bit platform).
Attention
For example, the following could be used to create a dynamic body having a one meter radius disk shape:
auto world = World{};
const auto body = world.CreateBody(BodyConf{}.UseType(BodyType::Dynamic));
const auto fixture = world.CreateFixture(
FixtureConf{}.UseBody(body).UseShape(DiskShapeConf{1_m}));
See also
BodyID, ContactID, FixtureID, JointID, Physical Entities.
https://en.wikipedia.org/wiki/Non-virtual_interface_pattern
https://en.wikipedia.org/wiki/Application_binary_interface
https://en.cppreference.com/w/cpp/language/pimpl
Examples
DistanceJoint.cpp, FrictionJoint.cpp, GearJoint.cpp, HelloWorld.cpp, MotorJoint.cpp, PrismaticJoint.cpp, PulleyJoint.cpp, RevoluteJoint.cpp, RopeJoint.cpp, TargetJoint.cpp, WeldJoint.cpp, WheelJoint.cpp, World.cpp, WorldBody.cpp, WorldContact.cpp, and WorldFixture.cpp.

Constructor & Destructor Documentation

◆ World() [1/2]

playrho::d2::World::World ( const WorldConf def = GetDefaultWorldConf())
explicit

Constructs a world object.

Parameters
defA customized world configuration or its default value.
Note
A lot more configurability can be had via the StepConf data that's given to the world's Step method.
Exceptions
InvalidArgumentif the given max vertex radius is less than the min.
See also
Step.

◆ World() [2/2]

playrho::d2::World::World ( const World other)

Copy constructor.

Copy constructs this world with a deep copy of the given world.

◆ ~World()

playrho::d2::World::~World ( )
noexcept

Destructor.

All physics entities are destroyed and all memory is released.

Note
This will call the Clear() function.
See also
Clear.

Member Function Documentation

◆ Clear()

void playrho::d2::World::Clear ( )
noexcept

Clears this world.

Note
This calls the joint and fixture destruction listeners (if they're set) before clearing anything.
Postcondition
The contents of this world have all been destroyed and this world's internal state is reset as though it had just been constructed.
Examples
World.cpp.

Referenced by playrho::d2::Clear().

◆ CreateBody()

BodyID playrho::d2::World::CreateBody ( const BodyConf def = GetDefaultBodyConf())

Creates a rigid body with the given configuration.

Warning
This function should not be used while the world is locked — as it is during callbacks. If it is, it will throw an exception or abort your program.
Note
No references to the configuration are retained. Its value is copied.
Postcondition
The created body will be present in the range returned from the GetBodies() method.
Parameters
defA customized body configuration or its default value.
Returns
Identifier of the newly created body which can later be destroyed by calling the Destroy(BodyID) method.
Exceptions
WrongStateif this method is called while the world is locked.
LengthErrorif this operation would create more than MaxBodies.
See also
Destroy(BodyID), GetBodies.
Physical Entities.
Examples
RevoluteJoint.cpp, TargetJoint.cpp, WheelJoint.cpp, and World.cpp.

Referenced by playrho::d2::CreateBody().

◆ CreateFixture()

FixtureID playrho::d2::World::CreateFixture ( const FixtureConf def = FixtureConf{})

Creates a fixture and attaches it to the identified body.

Creates a fixture for attaching a shape and other characteristics to this body. Fixtures automatically go away when this body is destroyed. Fixtures can also be manually removed and destroyed using the Destroy(FixtureID, bool), or DestroyFixtures() methods.

Warning
This function is locked during callbacks.
Note
This function should not be called if the world is locked.
This does not reset the associated body's mass data.
Postcondition
After creating a new fixture, it will show up in the fixture enumeration returned by the GetFixtures() methods.
Parameters
defInitial fixture settings. Friction and density must be >= 0. Restitution must be > -infinity and < infinity.
Returns
Identifier for the created fixture.
Exceptions
WrongStateif called while the world is "locked".
std::out_of_rangeIf given an invalid body identifier.
InvalidArgumentif called for a shape with a vertex radius less than the minimum vertex radius.
InvalidArgumentif called for a shape with a vertex radius greater than the maximum vertex radius.
See also
Destroy(FixtureID), GetFixtures
Physical Entities

Referenced by playrho::d2::CreateFixture().

◆ CreateJoint()

JointID playrho::d2::World::CreateJoint ( const Joint def)

Creates a joint to constrain one or more bodies.

Warning
This function is locked during callbacks.
Postcondition
The created joint will be present in the range returned from the GetJoints() method.
Returns
Identifier of newly created joint which can later be destroyed by calling the Destroy(JointID) method.
Exceptions
WrongStateif this method is called while the world is locked.
LengthErrorif this operation would create more than MaxJoints.
See also
Physical Entities.
Destroy(JointID), GetJoints.
Examples
World.cpp.

Referenced by playrho::d2::CreateJoint().

◆ Destroy() [1/3]

void playrho::d2::World::Destroy ( BodyID  id)

Destroys the identified body.

Destroys the identified body that had previously been created by a call to this world's CreateBody(const BodyConf&) method.

Warning
This automatically deletes all associated shapes and joints.
This function is locked during callbacks.
Behavior is undefined if the identified body was not created by this world.
Note
This function is locked during callbacks.
Postcondition
The destroyed body will no longer be present in the range returned from the GetBodies() method.
Parameters
idIdentifier of body to destroy that had been created by this world.
Exceptions
WrongStateif this method is called while the world is locked.
std::out_of_rangeIf given an invalid body identifier.
See also
CreateBody(const BodyConf&), GetBodies, GetBodyRange.
Physical Entities.
Examples
World.cpp.

Referenced by playrho::d2::Destroy(), and playrho::d2::DestroyFixtures().

◆ Destroy() [2/3]

bool playrho::d2::World::Destroy ( FixtureID  id)

Destroys the identified fixture.

Destroys a fixture previously created by the CreateFixture(const FixtureConf&) method. This removes the fixture from the broad-phase and destroys all contacts associated with this fixture. All fixtures attached to a body are implicitly destroyed when the body is destroyed.

Warning
This function is locked during callbacks.
Note
Make sure to explicitly call ResetMassData() after fixtures have been destroyed.
Exceptions
WrongStateif this function is called while the world is locked.
std::out_of_rangeIf given an invalid fixture identifier.
Postcondition
After destroying a fixture, it will no longer show up in the fixture enumeration returned by the GetFixtures() methods.
Parameters
idthe fixture to be removed.
See also
CreateFixture, GetFixtureRange.
Physical Entities.

◆ Destroy() [3/3]

void playrho::d2::World::Destroy ( JointID  id)

Destroys the identified joint.

Destroys the identified joint that had previously been created by a call to this world's CreateJoint(const Joint&) method.

Warning
This function is locked during callbacks.
Note
This may cause the connected bodies to begin colliding.
Postcondition
The destroyed joint will no longer be present in the range returned from the GetJoints() method.
Parameters
idIdentifier of joint to destroy that had been created by this world.
Exceptions
WrongStateif this method is called while the world is locked.
std::out_of_rangeIf given an invalid joint identifier.
See also
CreateJoint(const Joint&), GetJoints, GetJointRange.
Physical Entities.

◆ GetBodies()

SizedRange< World::Bodies::const_iterator > playrho::d2::World::GetBodies ( ) const
noexcept

Gets the world body range for this constant world.

Gets a range enumerating the bodies currently existing within this world. These are the bodies that had been created from previous calls to the CreateBody(const BodyConf&) method that haven't yet been destroyed.

Returns
Range of body identifiers that can be iterated over using its begin and end methods or using ranged-based for-loops.
See also
CreateBody(const BodyConf&).
Examples
World.cpp.

Referenced by playrho::d2::CalcGravitationalAcceleration(), and playrho::d2::GetShapeCount().

◆ GetBodiesForProxies()

SizedRange< World::Bodies::const_iterator > playrho::d2::World::GetBodiesForProxies ( ) const
noexcept

Gets the bodies-for-proxies range for this world.

Provides insight on what bodies have been queued for proxy processing during the next call to the world step method.

See also
Step.
Todo:
Remove this function from this class - access from implementation instead.
Examples
World.cpp.

◆ GetBody()

const Body & playrho::d2::World::GetBody ( BodyID  id) const

◆ GetBodyRange()

BodyCounter playrho::d2::World::GetBodyRange ( ) const
noexcept

Gets the extent of the currently valid body range.

Note
This is one higher than the maxium BodyID that is in range for body related functions.

◆ GetContact()

const Contact & playrho::d2::World::GetContact ( ContactID  id) const

Gets the identified contact.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.
See also
SetContact, GetContactRange.

Referenced by playrho::d2::GetContact(), playrho::d2::GetDefaultFriction(), and playrho::d2::GetDefaultRestitution().

◆ GetContactRange()

ContactCounter playrho::d2::World::GetContactRange ( ) const
noexcept

Gets the extent of the currently valid contact range.

Note
This is one higher than the maxium ContactID that is in range for contact related functions.

◆ GetContacts() [1/2]

SizedRange< World::Contacts::const_iterator > playrho::d2::World::GetContacts ( ) const
noexcept

Gets the world contact range.

Warning
contacts are created and destroyed in the middle of a time step. Use ContactListener to avoid missing contacts.
Returns
World contacts sized-range.

◆ GetContacts() [2/2]

SizedRange< World::Contacts::const_iterator > playrho::d2::World::GetContacts ( BodyID  id) const

Gets the container of contacts attached to the identified body.

Warning
This collection changes during the time step and you may miss some collisions if you don't use ContactListener.
Exceptions
std::out_of_rangeIf given an invalid body identifier.
See also
GetBodyRange.
Examples
World.cpp.

Referenced by playrho::d2::GetContacts().

◆ GetFixture()

◆ GetFixtureRange()

FixtureCounter playrho::d2::World::GetFixtureRange ( ) const
noexcept

Gets the extent of the currently valid fixture range.

Note
This is one higher than the maxium FixtureID that is in range for fixture related functions.

◆ GetFixtures()

SizedRange< World::Fixtures::const_iterator > playrho::d2::World::GetFixtures ( BodyID  id) const

Gets the range of fixtures attached to the identified body.

Exceptions
std::out_of_rangeIf given an invalid body identifier.
See also
CreateFixture, GetBodyRange.
Examples
World.cpp.

Referenced by playrho::d2::ComputeMassData(), playrho::d2::GetFixtures(), and playrho::d2::GetShapeCount().

◆ GetInvDeltaTime()

Frequency playrho::d2::World::GetInvDeltaTime ( ) const
noexcept

Gets the inverse delta time.

Gets the inverse delta time that was set on construction or assignment, and updated on every call to the Step() method having a non-zero delta-time.

See also
Step.

Referenced by playrho::d2::Step().

◆ GetJoint()

◆ GetJointRange()

JointCounter playrho::d2::World::GetJointRange ( ) const
noexcept

Gets the extent of the currently valid joint range.

Note
This is one higher than the maxium JointID that is in range for joint related functions.

◆ GetJoints() [1/2]

SizedRange< World::Joints::const_iterator > playrho::d2::World::GetJoints ( ) const
noexcept

Gets the world joint range.

Gets a range enumerating the joints currently existing within this world. These are the joints that had been created from previous calls to the CreateJoint method that haven't yet been destroyed.

Returns
World joints sized-range.
See also
CreateJoint.

◆ GetJoints() [2/2]

SizedRange< World::BodyJoints::const_iterator > playrho::d2::World::GetJoints ( BodyID  id) const

Gets the range of joints attached to the identified body.

Exceptions
std::out_of_rangeIf given an invalid body identifier.
See also
CreateJoint, GetBodyRange.
Examples
World.cpp.

Referenced by playrho::d2::GetJoints().

◆ GetManifold()

const Manifold & playrho::d2::World::GetManifold ( ContactID  id) const

Gets the collision manifold for the identified contact.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.
See also
GetContact, GetContactRange.

Referenced by playrho::d2::GetManifold().

◆ GetMaxVertexRadius()

Length playrho::d2::World::GetMaxVertexRadius ( ) const
noexcept

Gets the maximum vertex radius that shapes in this world can be.

See also
GetMinVertexRadius.
Examples
World.cpp.

Referenced by playrho::d2::GetMaxVertexRadius().

◆ GetMinVertexRadius()

Length playrho::d2::World::GetMinVertexRadius ( ) const
noexcept

Gets the minimum vertex radius that shapes in this world can be.

See also
GetMaxVertexRadius.
Examples
World.cpp.

Referenced by playrho::d2::GetMinVertexRadius().

◆ GetSubStepping()

bool playrho::d2::World::GetSubStepping ( ) const
noexcept

Gets whether or not sub-stepping is enabled.

See also
SetSubStepping, IsStepComplete.
Examples
World.cpp.

Referenced by playrho::d2::GetSubStepping().

◆ IsStepComplete()

bool playrho::d2::World::IsStepComplete ( ) const
noexcept

Whether or not "step" is complete.

The "step" is completed when there are no more TOI events for the current time step.

Returns
true unless sub-stepping is enabled and the step method returned without finishing all of its sub-steps.
See also
GetSubStepping, SetSubStepping.
Examples
World.cpp.

◆ operator=()

World & playrho::d2::World::operator= ( const World other)

Assignment operator.

Copy assigns this world with a deep copy of the given world.

◆ SetBody()

◆ SetContact()

void playrho::d2::World::SetContact ( ContactID  id,
const Contact value 
)

Sets the identified contact's state.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.
See also
GetContact, GetContactRange.

Referenced by playrho::d2::SetContact().

◆ SetFixture()

void playrho::d2::World::SetFixture ( FixtureID  id,
const FixtureConf value 
)

Sets the identified fixture's state.

Exceptions
std::out_of_rangeIf given an invalid fixture identifier.
See also
GetFixture, GetFixtureRange.

Referenced by playrho::d2::SetFilterData(), and playrho::d2::SetSensor().

◆ SetJoint()

void playrho::d2::World::SetJoint ( JointID  id,
const Joint def 
)

Sets the identified joint to the given value.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.
See also
GetJoint, GetJointRange.
Examples
World.cpp.

Referenced by playrho::d2::SetJoint().

◆ SetSubStepping()

void playrho::d2::World::SetSubStepping ( bool  flag)
noexcept

Enables/disables single stepped continuous physics.

Note
This is not normally used. Enabling sub-stepping is meant for testing.
Postcondition
The GetSubStepping() method will return the value this method was called with.
See also
IsStepComplete, GetSubStepping.
Examples
World.cpp.

Referenced by playrho::d2::SetSubStepping().

◆ ShiftOrigin()

void playrho::d2::World::ShiftOrigin ( Length2  newOrigin)

Shifts the world origin.

Note
Useful for large worlds.
The body shift formula is: position -= newOrigin.
Postcondition
The "origin" of this world's bodies, joints, and the board-phase dynamic tree have been translated per the shift amount and direction.
Parameters
newOriginthe new origin with respect to the old origin
Exceptions
WrongStateif this method is called while the world is locked.
Examples
World.cpp.

Referenced by playrho::d2::ShiftOrigin().

◆ Step()

StepStats playrho::d2::World::Step ( const StepConf conf = StepConf{})

Steps the world simulation according to the given configuration.

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.

Warning
Behavior is undefined if given a negative step time delta.
Varying the step time delta may lead to non-physical behaviors.
Note
Calling this with a zero step time delta results only in fixtures and bodies registered for special handling being processed. No physics is performed.
If the given velocity and position iterations are zero, this method doesn't do velocity or position resolutions respectively of the contacting bodies.
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 position 0 (p0) going velocity 0 (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.
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
confConfiguration for the simulation step.
Returns
Statistics for the step.
Exceptions
WrongStateif this method is called while the world is locked.
Examples
World.cpp.

Referenced by playrho::d2::Step().

Friends And Related Function Documentation

◆ ApplyAngularImpulse()

void ApplyAngularImpulse ( World world,
BodyID  id,
AngularMomentum  impulse 
)
related

Applies an angular impulse.

Parameters
worldThe world in which the identified body exists.
idIdentifier of body to apply the angular impulse to.
impulseAngular impulse to be applied.
Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ ApplyForce()

void ApplyForce ( World world,
BodyID  id,
Force2  force,
Length2  point 
)
related

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
worldWorld in which body exists.
idIdentity of body to apply the force to.
forceWorld force vector.
pointWorld position of the point of application.
Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ ApplyForceToCenter()

void ApplyForceToCenter ( World world,
BodyID  id,
Force2  force 
)
related

Applies a force to the center of mass of the given body.

Note
Non-zero forces wakes up the body.
Parameters
worldThe world in which the identified body exists.
idIdentifier of body to apply the force to.
forceWorld force vector.
Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ ApplyLinearImpulse()

void ApplyLinearImpulse ( World world,
BodyID  id,
Momentum2  impulse,
Length2  point 
)
related

Applies 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
worldThe world in which the identified body exists.
idIdentifier of body to apply the impulse to.
impulsethe world impulse vector.
pointthe world position of the point of application.
Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ ApplyTorque()

void ApplyTorque ( World world,
BodyID  id,
Torque  torque 
)
related

Applies 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
worldThe world in which the identified body exists.
idIdentifier of body to apply the torque to.
torqueabout the z-axis (out of the screen).
Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ Awaken() [1/2]

BodyCounter Awaken ( World world)
related

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.

◆ Awaken() [2/2]

bool Awaken ( World world,
BodyID  id 
)
related

Awakens the body if it's asleep.

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ CalcGravitationalAcceleration()

Acceleration CalcGravitationalAcceleration ( const World world,
BodyID  id 
)
related

Calculates the gravitationally associated acceleration for the given body within its world.

Returns
Zero acceleration if given body is has no mass, else the acceleration of the body due to the gravitational attraction to the other bodies.
Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ Clear()

void Clear ( World world)
related

Clears this world.

Note
This calls the joint and fixture destruction listeners (if they're set) before clearing anything.
Postcondition
The contents of this world have all been destroyed and this world's internal state is reset as though it had just been constructed.

◆ ClearForces()

void ClearForces ( World world)
related

Clears forces.

Manually clear the force buffer on all bodies.

◆ ComputeMassData()

MassData ComputeMassData ( const World world,
BodyID  id 
)
related

Computes the identified 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
accumulated mass data for all fixtures associated with the given body.
Exceptions
std::out_of_rangeIf given an invalid body identifier.
Examples
World.cpp.

◆ CreateBody()

BodyID CreateBody ( World world,
const BodyConf def = GetDefaultBodyConf() 
)
related

Creates a rigid body with the given configuration.

Warning
This function should not be used while the world is locked — as it is during callbacks. If it is, it will throw an exception or abort your program.
Note
No references to the configuration are retained. Its value is copied.
Postcondition
The created body will be present in the range returned from the GetBodies(const World&) method.
Parameters
worldThe world within which to create the body.
defA customized body configuration or its default value.
Returns
Identifier of the newly created body which can later be destroyed by calling the Destroy(World&, BodyID) method.
Exceptions
WrongStateif this method is called while the world is locked.
LengthErrorif this operation would create more than MaxBodies.
See also
Destroy(World& world, BodyID), GetBodies(const World&).
Physical Entities.

◆ CreateFixture() [1/3]

FixtureID CreateFixture ( World world,
BodyID  id,
const Shape shape,
FixtureConf  def = FixtureConf{},
bool  resetMassData = true 
)
related

Creates a fixture within the specified world.

Exceptions
WrongStateif called while the world is "locked".
std::out_of_rangeIf given an invalid body identifier.
See also
CreateFixture(World& world, FixtureConf def).

◆ CreateFixture() [2/3]

template<typename T >
FixtureID CreateFixture ( World world,
BodyID  id,
const T &  shapeConf,
FixtureConf  def = FixtureConf{},
bool  resetMassData = true 
)
related

Creates a fixture within the specified world using a configuration of a shape.

This is a convenience function for allowing limited implicit conversions to shapes.

Exceptions
WrongStateif called while the world is "locked".
std::out_of_rangeIf given an invalid body identifier.
See also
CreateFixture(World& world, FixtureConf def).

◆ CreateFixture() [3/3]

FixtureID CreateFixture ( World world,
FixtureConf  def = FixtureConf{},
bool  resetMassData = true 
)
related

Creates a fixture within the specified world.

Exceptions
WrongStateif called while the world is "locked".
std::out_of_rangeIf given an invalid body identifier in the configuration.
See also
CreateFixture(World&, BodyID, const Shape&,FixtureConf,bool).
Examples
World.cpp.

◆ CreateJoint()

template<typename T >
JointID CreateJoint ( World world,
const T &  value 
)
related

Creates a new joint from a configuration.

This is a convenience function for allowing limited implicit conversions to joints.

◆ Destroy() [1/3]

void Destroy ( World world,
BodyID  id 
)
related

Destroys the identified body.

Exceptions
std::out_of_rangeIf given an invalid body identifier.
See also
CreateBody(World&, const BodyConf&).

◆ Destroy() [2/3]

bool Destroy ( World world,
FixtureID  id,
bool  resetMassData = true 
)
related

Destroys the identified fixture.

Exceptions
WrongStateif this function is called while the world is locked.
std::out_of_rangeIf given an invalid fixture identifier.

◆ Destroy() [3/3]

void Destroy ( World world,
JointID  id 
)
related

Destroys the identified joint.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ DestroyFixtures()

void DestroyFixtures ( World world,
BodyID  id,
bool  resetMassData = true 
)
related

Destroys fixtures of the identified body.

Destroys all of the fixtures previously created for this body by the CreateFixture(const Shape&, const FixtureConf&, bool) method.

Note
This may call the ResetMassData() method.
Postcondition
After this call, no fixtures will show up in the fixture enumeration returned by the GetFixtures() methods.
Exceptions
std::out_of_rangeIf given an invalid body identifier.
See also
CreateFixture, GetFixtures, ResetMassData.
Physical Entities

◆ EnableLimit()

void EnableLimit ( World world,
JointID  id,
bool  value 
)
related

Sets whether the identified joint's limit is enabled or not.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ EnableMotor()

void EnableMotor ( World world,
JointID  id,
bool  value 
)
related

Enable/disable the joint motor.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetAcceleration()

Acceleration GetAcceleration ( const World world,
BodyID  id 
)
related

Gets the acceleration of the identified body.

Exceptions
std::out_of_rangeIf given an invalid body identifier.
See also
SetAcceleration(World&, BodyID, LinearAcceleration2, AngularAcceleration).

◆ GetAnchorA()

Length2 GetAnchorA ( const World world,
JointID  id 
)
related

Get the anchor point on body-A in world coordinates.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetAnchorB()

Length2 GetAnchorB ( const World world,
JointID  id 
)
related

Get the anchor point on body-B in world coordinates.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetAngle() [1/2]

Angle GetAngle ( const World world,
BodyID  id 
)
related

Gets the angle of the identified body.

Returns
the current world rotation angle.
Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ GetAngle() [2/2]

Angle GetAngle ( const World world,
JointID  id 
)
related

Gets the angle property of the identified joint if it has it.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetAngularAcceleration()

AngularAcceleration GetAngularAcceleration ( const World world,
BodyID  id 
)
related

Gets this body's angular acceleration.

Exceptions
std::out_of_rangeIf given an invalid body identifier.
See also
GetAcceleration(const World& world, BodyID id).

◆ GetAngularDamping()

Frequency GetAngularDamping ( const World world,
BodyID  id 
)
related

Gets the angular damping of the body.

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ GetAngularLowerLimit()

Angle GetAngularLowerLimit ( const World world,
JointID  id 
)
related

Get the lower joint limit.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetAngularMass()

RotInertia GetAngularMass ( const World world,
JointID  id 
)
related

Gets the computed angular rotational inertia used by the joint.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetAngularMotorImpulse()

AngularMomentum GetAngularMotorImpulse ( const World world,
JointID  id 
)
related

Gets the angular motor impulse of the identified joint if it has this property.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetAngularOffset()

Angle GetAngularOffset ( const World world,
JointID  id 
)
related

Gets the target angular offset.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetAngularReaction()

AngularMomentum GetAngularReaction ( const World world,
JointID  id 
)
related

Get the angular reaction on body-B for the identified joint.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetAngularUpperLimit()

Angle GetAngularUpperLimit ( const World world,
JointID  id 
)
related

Get the upper joint limit.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetAngularVelocity() [1/2]

AngularVelocity GetAngularVelocity ( const World world,
BodyID  id 
)
related

Gets the angular velocity.

Parameters
worldWorld in which body is identified for.
idIdentifier of body to get the angular velocity for.
Returns
the angular velocity.
Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ GetAngularVelocity() [2/2]

AngularVelocity GetAngularVelocity ( const World world,
JointID  id 
)
related

Gets the angular velocity of the identified joint if it has this property.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetBody() [1/2]

const Body & GetBody ( const World world,
BodyID  id 
)
related

Gets the body configuration for the identified body.

Exceptions
std::out_of_rangeIf given an invalid body identifier.
See also
CreateBody(World& world, const BodyConf&), SetBody(World& world, BodyID id, const Body& body).

◆ GetBody() [2/2]

BodyID GetBody ( const World world,
FixtureID  id 
)
related

Gets the identifier of the body associated with the identified fixture.

Exceptions
std::out_of_rangeIf given an invalid fixture identifier.

◆ GetBodyA() [1/2]

BodyID GetBodyA ( const World world,
ContactID  id 
)
related

Gets the body-A of the identified contact if it has one.

Returns
Identification of the body-A or InvalidBodyID.
Exceptions
std::out_of_rangeIf given an invalid contact identifier.

◆ GetBodyA() [2/2]

BodyID GetBodyA ( const World world,
JointID  id 
)
related

Gets the identifier of body-A of the identified joint.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetBodyB() [1/2]

BodyID GetBodyB ( const World world,
ContactID  id 
)
related

Gets the body-B of the identified contact if it has one.

Returns
Identification of the body-B or InvalidBodyID.
Exceptions
std::out_of_rangeIf given an invalid contact identifier.

◆ GetBodyB() [2/2]

BodyID GetBodyB ( const World world,
JointID  id 
)
related

Gets the identifier of body-B of the identified joint.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetBodyCount()

BodyCounter GetBodyCount ( const World world)
related

Gets the body count in the given world.

Returns
0 or higher.

◆ GetBodyRange()

BodyCounter GetBodyRange ( const World world)
related

Gets the extent of the currently valid body range.

Note
This is one higher than the maxium BodyID that is in range for body related functions.

◆ GetCentripetalForce()

Force2 GetCentripetalForce ( const World world,
BodyID  id,
Length2  axis 
)
related

Gets the centripetal force necessary to put the body into an orbit having the given radius.

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ GetChildIndexA()

ChildCounter GetChildIndexA ( const World world,
ContactID  id 
)
related

Get the child primitive index for fixture A.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.

◆ GetChildIndexB()

ChildCounter GetChildIndexB ( const World world,
ContactID  id 
)
related

Get the child primitive index for fixture B.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.

◆ GetCollideConnected()

bool GetCollideConnected ( const World world,
JointID  id 
)
related

Gets collide connected for the specified joint.

Note
Modifying the collide connect flag won't work correctly because the flag is only checked when fixture AABBs begin to overlap.
Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetContact()

const Contact & GetContact ( const World world,
ContactID  id 
)
related

Gets the identified contact.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.

◆ GetContactCount()

ContactCounter GetContactCount ( const World world)
related

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.

◆ GetContactRange()

ContactCounter GetContactRange ( const World world)
related

Gets the extent of the currently valid contact range.

Note
This is one higher than the maxium ContactID that is in range for contact related functions.

◆ GetContacts()

SizedRange< std::vector< KeyedContactPtr >::const_iterator > GetContacts ( const World world,
BodyID  id 
)
related

Gets the container of all contacts attached to the identified body.

Warning
This collection changes during the time step and you may miss some collisions if you don't use ContactListener.
Exceptions
std::out_of_rangeIf given an invalid body identifier.
Examples
World.cpp.

◆ GetCurrentLengthA()

Length GetCurrentLengthA ( const World world,
JointID  id 
)
related

Get the current length of the segment attached to body-A.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetCurrentLengthB()

Length GetCurrentLengthB ( const World world,
JointID  id 
)
related

Get the current length of the segment attached to body-B.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetDampingRatio()

Real GetDampingRatio ( const World world,
JointID  id 
)
related

Gets the damping ratio associated with the identified joint if it has one.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.
std::invalid_argumentIf the identified joint's type doesn't support this.

◆ GetDefaultFriction()

Real GetDefaultFriction ( const World world,
ContactID  id 
)
related

Gets the default friction amount for the identified contact.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.
See also
SetFriction.

◆ GetDefaultRestitution()

Real GetDefaultRestitution ( const World world,
ContactID  id 
)
related

Gets the default restitution amount for the identified contact.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.
See also
SetRestitution.

◆ GetDensity()

AreaDensity GetDensity ( const World world,
FixtureID  id 
)
related

Gets the density of this fixture.

Returns
Non-negative density (in mass per area).
Exceptions
std::out_of_rangeIf given an invalid fixture identifier.

◆ GetFilterData()

Filter GetFilterData ( const World world,
FixtureID  id 
)
related

Gets the filter data for the identified fixture.

Exceptions
std::out_of_rangeIf given an invalid fixture identifier.
See also
SetFilterData.

◆ GetFixtureA()

FixtureID GetFixtureA ( const World world,
ContactID  id 
)
related

Gets fixture A of the identified contact.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.

◆ GetFixtureB()

FixtureID GetFixtureB ( const World world,
ContactID  id 
)
related

Gets fixture B of the identified contact.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.

◆ GetFixtureCount() [1/2]

FixtureCounter GetFixtureCount ( const World world)
related

Gets the count of fixtures in the given world.

Returns
Value that's less than or equal to what's returned by GetFixtureRange(const World& world).
Exceptions
WrongStateif called while the world is "locked".
See also
GetFixtureRange(const World& world).

◆ GetFixtureCount() [2/2]

FixtureCounter GetFixtureCount ( const World world,
BodyID  id 
)
related

Gets the count of fixtures associated with the identified body.

Exceptions
std::out_of_rangeIf given an invalid body identifier.
See also
GetFixtures(const World& world, BodyID id).

◆ GetFixtureRange()

FixtureCounter GetFixtureRange ( const World world)
related

Gets the extent of the currently valid fixture range.

Note
This is one higher than the maxium FixtureID that is in range for fixture related functions.
See also
CreateFixture(World& world, FixtureConf).

◆ GetFixtures()

SizedRange< std::vector< FixtureID >::const_iterator > GetFixtures ( const World world,
BodyID  id 
)
related

Gets the range of all constant fixtures attached to the given body.

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ GetFrequency()

Frequency GetFrequency ( const World world,
JointID  id 
)
related

Gets the frequency of the identified joint if it has this property.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetFriction() [1/2]

Real GetFriction ( const World world,
ContactID  id 
)
related

Gets the friction used with the identified contact.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.
See also
SetFriction.

◆ GetFriction() [2/2]

Real GetFriction ( const World world,
FixtureID  id 
)
related

Gets the coefficient of friction of the specified fixture.

Returns
Value of 0 or higher.
Exceptions
std::out_of_rangeIf given an invalid fixture identifier.

◆ GetGroundAnchorA()

Length2 GetGroundAnchorA ( const World world,
JointID  id 
)
related

Get the first ground anchor.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetGroundAnchorB()

Length2 GetGroundAnchorB ( const World world,
JointID  id 
)
related

Get the second ground anchor.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetInvMass()

InvMass GetInvMass ( const World world,
BodyID  id 
)
related

Gets the inverse total mass of the body.

Returns
Value of zero or more representing the body's inverse mass (in 1/kg).
Exceptions
std::out_of_rangeIf given an invalid body identifier.
See also
SetMassData.

◆ GetInvRotInertia()

InvRotInertia GetInvRotInertia ( const World world,
BodyID  id 
)
related

Gets the inverse rotational inertia of the body.

Returns
Inverse rotational inertia (in 1/kg-m^2).
Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ GetJoint()

const Joint & GetJoint ( const World world,
JointID  id 
)
related

Gets the value of the identified joint.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetJointCount()

JointCounter GetJointCount ( const World world)
related

Gets the count of joints in the given world.

Returns
0 or higher.

◆ GetJointRange()

JointCounter GetJointRange ( const World world)
related

Gets the extent of the currently valid joint range.

Note
This is one higher than the maxium JointID that is in range for joint related functions.

◆ GetJoints()

SizedRange< std::vector< std::pair< BodyID, JointID > >::const_iterator > GetJoints ( const World world,
BodyID  id 
)
related

Gets the range of all joints attached to the identified body.

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ GetJointTranslation()

Length GetJointTranslation ( const World world,
JointID  id 
)
related

Gets the current joint translation.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetLength()

Length GetLength ( const World world,
JointID  id 
)
related

Gets the length associated with the identified joint if it has one.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.
std::invalid_argumentIf the identified joint's type doesn't support this.

◆ GetLimitState()

LimitState GetLimitState ( const World world,
JointID  id 
)
related

Gets the joint's limit state if it has one.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.
std::invalid_argumentIf the identified joint's type doesn't support this.

◆ GetLinearAcceleration()

LinearAcceleration2 GetLinearAcceleration ( const World world,
BodyID  id 
)
related

Gets this body's linear acceleration.

Exceptions
std::out_of_rangeIf given an invalid body identifier.
See also
GetAcceleration(const World& world, BodyID id).

◆ GetLinearDamping()

Frequency GetLinearDamping ( const World world,
BodyID  id 
)
related

Gets the linear damping of the body.

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ GetLinearMotorImpulse()

Momentum GetLinearMotorImpulse ( const World world,
JointID  id 
)
related

Gets the linear motor impulse of the identified joint if it supports that.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetLinearOffset()

Length2 GetLinearOffset ( const World world,
JointID  id 
)
related

Gets the target linear offset, in frame A.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetLinearReaction()

Momentum2 GetLinearReaction ( const World world,
JointID  id 
)
related

Gets the linear reaction on body-B at the joint anchor.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetLinearVelocity()

LinearVelocity2 GetLinearVelocity ( const World world,
BodyID  id 
)
related

Gets the linear velocity of the center of mass of the identified body.

Parameters
worldWorld in which body is identified for.
idIdentifier of body to get the linear velocity for.
Returns
the linear velocity of the center of mass.
Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ GetLocalAnchorA()

Length2 GetLocalAnchorA ( const World world,
JointID  id 
)
related

Get the anchor point on body-A in local coordinates.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetLocalAnchorB()

Length2 GetLocalAnchorB ( const World world,
JointID  id 
)
related

Get the anchor point on body-B in local coordinates.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetLocalCenter()

Length2 GetLocalCenter ( const World world,
BodyID  id 
)
related

Gets the local position of the center of mass of the specified body.

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ GetLocalPoint()

Length2 GetLocalPoint ( const World world,
BodyID  body,
const Length2  worldPoint 
)
related

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

Parameters
worldThe world in which the identified body exists.
bodyIdentifier of body that the returned point should be relative to.
worldPointpoint in world coordinates.
Returns
the corresponding local point relative to the body's origin.
Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ GetLocalRotInertia()

RotInertia GetLocalRotInertia ( const World world,
BodyID  id 
)
related

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

Returns
the rotational inertia.
Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ GetLocalVector()

UnitVec GetLocalVector ( const World world,
BodyID  body,
const UnitVec  uv 
)
related

Convenience function for getting the local vector of the identified body.

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ GetLocalXAxisA()

UnitVec GetLocalXAxisA ( const World world,
JointID  id 
)
related

Gets the local-X-axis-A property of the identified joint if it has it.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetLocalYAxisA()

UnitVec GetLocalYAxisA ( const World world,
JointID  id 
)
related

Gets the local-Y-axis-A property of the identified joint if it has it.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetLocation()

Length2 GetLocation ( const World world,
BodyID  id 
)
related

Convenience function for getting just the location of the identified body.

Exceptions
std::out_of_rangeIf given an invalid body identifier.
See also
GetTransformation(const World& world, BodyID id).

◆ GetManifold()

const Manifold & GetManifold ( const World world,
ContactID  id 
)
related

Gets the manifold for the identified contact.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.
Examples
World.cpp.

◆ GetMass()

Mass GetMass ( const World world,
BodyID  id 
)
related

Gets the mass of the body.

Note
This may be the total calculated mass or it may be the set mass of the body.
Returns
Value of zero or more representing the body's mass.
Exceptions
std::out_of_rangeIf given an invalid body identifier.
See also
GetInvMass, SetMassData

◆ GetMassData() [1/2]

MassData GetMassData ( const World world,
BodyID  id 
)
related

Gets the mass data of the body.

Returns
Data structure containing the mass, inertia, and center of the body.
Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ GetMassData() [2/2]

MassData GetMassData ( const World world,
FixtureID  id 
)
related

Gets the mass data for the identified fixture in the given world.

Exceptions
std::out_of_rangeIf given an invalid fixture identifier.

◆ GetMaxMotorTorque()

Torque GetMaxMotorTorque ( const World world,
JointID  id 
)
related

Gets the max motor torque.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetMotorForce()

Force GetMotorForce ( const World world,
JointID  id,
Frequency  inv_dt 
)
related

Gets the current motor force for the given joint, given the inverse time step.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetMotorSpeed()

AngularVelocity GetMotorSpeed ( const World world,
JointID  id 
)
related

Gets the motor-speed property of the identied joint if it supports it.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.
See also
SetMotorSpeed(World& world, JointID id, AngularVelocity value)

◆ GetMotorTorque()

Torque GetMotorTorque ( const World world,
JointID  id,
Frequency  inv_dt 
)
related

Gets the current motor torque for the given joint given the inverse time step.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetRatio()

Real GetRatio ( const World world,
JointID  id 
)
related

Gets the ratio property of the identified joint if it has it.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetReferenceAngle()

Angle GetReferenceAngle ( const World world,
JointID  id 
)
related

Gets the reference-angle property of the identified joint if it has it.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetRestitution() [1/2]

Real GetRestitution ( const World world,
ContactID  id 
)
related

Gets the restitution used with the identified contact.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.
See also
SetRestitution(World& world, ContactID id, Real restitution)

◆ GetRestitution() [2/2]

Real GetRestitution ( const World world,
FixtureID  id 
)
related

Gets the coefficient of restitution of the specified fixture.

Exceptions
std::out_of_rangeIf given an invalid fixture identifier.

◆ GetRotInertia()

RotInertia GetRotInertia ( const World world,
BodyID  id 
)
related

Gets the rotational inertia of the body.

Parameters
worldThe world in which the identified body exists.
idIdentifier of body to get the rotational inertia for.
Returns
the rotational inertia.
Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ GetShape()

const Shape & GetShape ( const World world,
FixtureID  id 
)
related

Gets the shape associated with the identified fixture.

Exceptions
std::out_of_rangeIf given an invalid fixture identifier.

◆ GetSubStepping()

bool GetSubStepping ( const World world)
related

Gets whether or not sub-stepping is enabled.

See also
SetSubStepping, IsStepComplete.

◆ GetTangentSpeed()

LinearVelocity GetTangentSpeed ( const World world,
ContactID  id 
)
related

Gets the tangent speed of the identified contact.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.

◆ GetTarget()

Length2 GetTarget ( const World world,
JointID  id 
)
related

Gets the target point.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetToi()

Real GetToi ( const World world,
ContactID  id 
)
related

Gets the time of impact (TOI) as a fraction.

Note
This is only valid if a TOI has been set.
Returns
Time of impact fraction in the range of 0 to 1 if set (where 1 means no actual impact in current time slot), otherwise undefined.
Exceptions
std::out_of_rangeIf given an invalid contact identifier.
See also
HasValidToi.

◆ GetToiCount()

TimestepIters GetToiCount ( const World world,
ContactID  id 
)
related

Gets the Time Of Impact (TOI) count.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.

◆ GetTransformation() [1/2]

Transformation GetTransformation ( const World world,
BodyID  id 
)
related

Gets the body's transformation.

Exceptions
std::out_of_rangeIf given an invalid body identifier.
See also
SetTransformation(World& world, BodyID id, Transformation xfm).

◆ GetTransformation() [2/2]

Transformation GetTransformation ( const World world,
FixtureID  id 
)
related

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.
Exceptions
std::out_of_rangeIf given an invalid fixture identifier.

◆ GetType() [1/2]

BodyType GetType ( const World world,
BodyID  id 
)
related

Gets the type of the identified body.

See also
SetType(World& world, BodyID id, BodyType value)

◆ GetType() [2/2]

TypeID GetType ( const World world,
JointID  id 
)
related

Gets the type of the joint.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetVelocity()

Velocity GetVelocity ( const World world,
BodyID  id 
)
related

Gets the velocity of the identified body.

Exceptions
std::out_of_rangeIf given an invalid body identifier.
See also
SetVelocity(World& world, BodyID id, const Velocity& value).

◆ GetWorldCenter()

Length2 GetWorldCenter ( const World world,
BodyID  id 
)
related

Get the world position of the center of mass of the specified body.

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ GetWorldIndex() [1/2]

BodyCounter GetWorldIndex ( const World world,
const BodyID  id 
)
related

Gets the world index for the given body.

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ GetWorldIndex() [2/2]

JointCounter GetWorldIndex ( const World world,
JointID  id 
)
related

Gets the world index of the given joint.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetWorldManifold()

WorldManifold GetWorldManifold ( const World world,
ContactID  id 
)
related

Gets the world manifold for the identified contact.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.

◆ GetWorldPoint()

Length2 GetWorldPoint ( const World world,
BodyID  id,
const Length2  localPoint 
)
related

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

Parameters
worldWorld context.
idIdentifier of body that the given point is relative to.
localPointa point measured relative the the body's origin.
Returns
the same point expressed in world coordinates.
Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ HasValidToi()

bool HasValidToi ( const World world,
ContactID  id 
)
related

Whether or not the contact has a valid TOI.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.
See also
GetToi.

◆ IsAccelerable()

bool IsAccelerable ( const World world,
BodyID  id 
)
related

Is identified body "accelerable"?

Indicates whether the body is accelerable, i.e. whether it is effected by forces. Only Dynamic bodies are accelerable.

Returns
true if the body is accelerable, false otherwise.
Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ IsAwake() [1/3]

bool IsAwake ( const World world,
BodyID  id 
)
related

Gets the awake/asleep state of this body.

Warning
Being awake may or may not imply being speedable.
Returns
true if the body is awake.
Exceptions
std::out_of_rangeIf given an invalid body identifier.
See also
SetAwake(World& world, BodyID id), UnsetAwake(BodyID id).

◆ IsAwake() [2/3]

bool IsAwake ( const World world,
BodyID  id 
)
related

Gets the awake/asleep state of this body.

Warning
Being awake may or may not imply being speedable.
Returns
true if the body is awake.
Exceptions
std::out_of_rangeIf given an invalid body identifier.
See also
SetAwake, UnsetAwake.

◆ IsAwake() [3/3]

bool IsAwake ( const World world,
ContactID  id 
)
related

Gets the awake status of the specified contact.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.
See also
SetAwake.

◆ IsEnabled() [1/3]

bool IsEnabled ( const World world,
BodyID  id 
)
related

Gets the enabled/disabled state of the body.

Exceptions
std::out_of_rangeIf given an invalid body identifier.
See also
SetEnabled.

◆ IsEnabled() [2/3]

bool IsEnabled ( const World world,
ContactID  id 
)
related

Gets the enabled status of the identified contact.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.

◆ IsEnabled() [3/3]

bool IsEnabled ( const World world,
JointID  id 
)
related

Gets the enabled/disabled state of the joint.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ IsFixedRotation()

bool IsFixedRotation ( const World world,
BodyID  id 
)
related

Gets whether the body has fixed rotation.

Exceptions
std::out_of_rangeIf given an invalid body identifier.
See also
SetFixedRotation.

◆ IsImpenetrable()

bool IsImpenetrable ( const World world,
BodyID  id 
)
related

Is the body treated like a bullet for continuous collision detection?

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ IsLimitEnabled()

bool IsLimitEnabled ( const World world,
JointID  id 
)
related

Gets whether the identified joint's limit is enabled.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ IsMassDataDirty()

bool IsMassDataDirty ( const World world,
BodyID  id 
)
related

Gets whether the body's mass-data is dirty.

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ IsMotorEnabled()

bool IsMotorEnabled ( const World world,
JointID  id 
)
related

Is the joint motor enabled?

Exceptions
std::out_of_rangeIf given an invalid joint identifier.
See also
EnableMotor(World& world, JointID joint, bool value)

◆ IsSensor()

bool IsSensor ( const World world,
FixtureID  id 
)
related

Is the specified fixture a sensor (non-solid)?

Returns
the true if the fixture is a sensor.
Exceptions
std::out_of_rangeIf given an invalid fixture identifier.
See also
SetSensor.

◆ IsSleepingAllowed()

bool IsSleepingAllowed ( const World world,
BodyID  id 
)
related

Gets whether the identified body is allowed to sleep.

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ IsSpeedable()

bool IsSpeedable ( const World world,
BodyID  id 
)
related

Is identified body "speedable".

Is the body able to have a non-zero speed associated with it. Kinematic and Dynamic bodies are speedable. Static bodies are not.

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ IsTouching()

bool IsTouching ( const World world,
ContactID  id 
)
related

Is this contact touching?

Touching is defined as either:

  1. This contact's manifold has more than 0 contact points, or
  2. This contact has sensors and the two shapes of this contact are found to be overlapping.
    Returns
    true if this contact is said to be touching, false otherwise.
    Exceptions
    std::out_of_rangeIf given an invalid contact identifier.

◆ NeedsFiltering()

bool NeedsFiltering ( const World world,
ContactID  id 
)
related

Whether or not the contact needs filtering.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.

◆ NeedsUpdating()

bool NeedsUpdating ( const World world,
ContactID  id 
)
related

Whether or not the contact needs updating.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.

◆ ResetFriction()

void ResetFriction ( World world,
ContactID  id 
)
related

Resets the friction mixture to the default value.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.

◆ ResetMassData()

void ResetMassData ( World world,
BodyID  id 
)
related

Resets the mass data properties.

This resets the mass data to the sum of the mass properties of the fixtures.

Note
This method must be called after calling CreateFixture to update the body mass data properties unless SetMassData is used.
Exceptions
std::out_of_rangeIf given an invalid body identifier.
See also
SetMassData.

◆ ResetRestitution()

void ResetRestitution ( World world,
ContactID  id 
)
related

Resets the restitution to the default value.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.

◆ RotateAboutLocalPoint()

void RotateAboutLocalPoint ( World world,
BodyID  id,
Angle  amount,
Length2  localPoint 
)
related

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
worldThe world in which the identified body exists.
idIdentifier of body to rotate.
amountAmount to rotate body by (in counter-clockwise direction).
localPointPoint in local coordinates.
Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ RotateAboutWorldPoint()

void RotateAboutWorldPoint ( World world,
BodyID  id,
Angle  amount,
Length2  worldPoint 
)
related

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
worldThe world in which the identified body exists.
idIdentifier of body to rotate.
amountAmount to rotate body by (in counter-clockwise direction).
worldPointPoint in world coordinates.
Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ SetAcceleration() [1/4]

void SetAcceleration ( World world,
BodyID  id,
Acceleration  value 
)
related

Sets the accelerations on the given body.

Note
This has no effect on non-accelerable bodies.
A non-zero acceleration will also awaken the body.
Parameters
worldThe world in which the identified body's acceleration should be set.
idIdentifier of body whose acceleration should be set.
valueAcceleration value to set.
Exceptions
std::out_of_rangeIf given an invalid body identifier.
See also
GetAcceleration(const World& world, BodyID id).

◆ SetAcceleration() [2/4]

void SetAcceleration ( World world,
BodyID  id,
AngularAcceleration  value 
)
related

Sets the rotational accelerations on the body.

Note
This has no effect on non-accelerable bodies.
A non-zero acceleration will also awaken the body.
Exceptions
std::out_of_rangeIf given an invalid body identifier.
See also
GetAcceleration(const World& world, BodyID id).

◆ SetAcceleration() [3/4]

void SetAcceleration ( World world,
BodyID  id,
LinearAcceleration2  linear,
AngularAcceleration  angular 
)
related

Sets the linear and rotational accelerations on the body.

Note
This has no effect on non-accelerable bodies.
A non-zero acceleration will also awaken the body.
Parameters
worldWorld in which it all happens.
idIdentifier of body whose acceleration should be set.
linearLinear acceleration.
angularAngular acceleration.
Exceptions
std::out_of_rangeIf given an invalid body identifier.
See also
GetAcceleration(const World& world, BodyID id).

◆ SetAcceleration() [4/4]

void SetAcceleration ( World world,
BodyID  id,
LinearAcceleration2  value 
)
related

Sets the linear accelerations on the body.

Note
This has no effect on non-accelerable bodies.
A non-zero acceleration will also awaken the body.
Exceptions
std::out_of_rangeIf given an invalid body identifier.
See also
GetAcceleration(const World& world, BodyID id).

◆ SetAccelerations() [1/2]

template<class F >
void SetAccelerations ( World world,
fn 
)
related

Sets the accelerations of all the world's bodies.

Parameters
worldWorld instance to set the acceleration of all contained bodies for.
fnFunction or functor with a signature like: Acceleration (*fn)(World&,BodyID).

◆ SetAccelerations() [2/2]

void SetAccelerations ( World world,
LinearAcceleration2  acceleration 
)
related

Sets the accelerations of all the world's bodies to the given value.

Note
This will leave the angular acceleration alone.

◆ SetAngle()

void SetAngle ( World world,
BodyID  id,
Angle  value 
)
related

Sets the body's angular orientation.

This instantly adjusts the body to be at the new angular orientation.

Warning
Manipulating a body's angle this way can cause non-physical behavior!
Parameters
worldThe world in which the identified body's angle should be set.
idIdentifier of body to move.
valueValid world angle of the body's local origin. Behavior is undefined if value is invalid.
Exceptions
std::out_of_rangeIf given an invalid body identifier.
See also
GetAngle(const World& world, BodyID id).

◆ SetAngularDamping()

void SetAngularDamping ( World world,
BodyID  id,
NonNegative< Frequency angularDamping 
)
related

Sets the angular damping of the body.

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ SetAngularLimits()

void SetAngularLimits ( World world,
JointID  id,
Angle  lower,
Angle  upper 
)
related

Set the joint limits.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ SetAngularOffset()

void SetAngularOffset ( World world,
JointID  id,
Angle  value 
)
related

Sets the target angular offset.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ SetAwake() [1/4]

void SetAwake ( World world,
BodyID  id 
)
related

Wakes up the identified body.

Note
This wakes up any associated contacts that had been asleep.
Exceptions
std::out_of_rangeIf given an invalid body identifier.
See also
IsAwake(const World& world, BodyID id), UnsetAwake(World& world, BodyID id).

◆ SetAwake() [2/4]

void SetAwake ( World world,
BodyID  id 
)
related

Wakes up the identified body.

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ SetAwake() [3/4]

void SetAwake ( World world,
ContactID  id 
)
related

Sets awake the bodies of the fixtures of the given contact.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.

◆ SetAwake() [4/4]

void SetAwake ( World world,
JointID  id 
)
related

Wakes up the joined bodies.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ SetBody()

void SetBody ( World world,
BodyID  id,
const Body body 
)
related

Sets the body state for the identified body.

Exceptions
std::out_of_rangeIf given an invalid body identifier.
See also
GetBody(const World& world, BodyID id).

◆ SetContact()

void SetContact ( World world,
ContactID  id,
const Contact value 
)
related

Sets the identified contact's state.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.

◆ SetEnabled() [1/3]

void SetEnabled ( World world,
BodyID  id,
bool  value 
)
related

Sets the enabled state of the body.

A disabled body is not simulated and cannot be collided with or woken up. If you pass a flag of true, all fixtures will be added to the broad-phase. If you pass a flag of false, all fixtures will be removed from the broad-phase and all contacts will be destroyed. Fixtures and joints are otherwise unaffected.

Note
A disabled body is still owned by a World object and remains in the world's body container.
You may continue to create/destroy fixtures and joints on disabled bodies.
Fixtures on a disabled body are implicitly disabled and will not participate in collisions, ray-casts, or queries.
Joints connected to a disabled body are implicitly disabled.
Exceptions
WrongStateIf call would change body's state when world is locked.
std::out_of_rangeIf given an invalid body identifier.
Postcondition
IsEnabled() returns the state given to this function.
See also
IsEnabled.

◆ SetEnabled() [2/3]

void SetEnabled ( World world,
ContactID  id 
)
related

Sets the enabled status of the identified contact.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.

◆ SetEnabled() [3/3]

void SetEnabled ( World world,
ContactID  id,
bool  value 
)
related

Convenience function for setting/unsetting the enabled status of the identified contact based on the value parameter.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.
See also
IsEnabled(const World&, ContactID).

◆ SetFilterData()

void SetFilterData ( World world,
FixtureID  id,
const Filter filter 
)
related

Sets the contact filtering data.

Note
This won't update contacts until the next time step when either parent body is speedable and awake.
This automatically refilters contacts.
Exceptions
std::out_of_rangeIf given an invalid fixture identifier.
See also
GetFilterData.

◆ SetFixedRotation()

void SetFixedRotation ( World world,
BodyID  id,
bool  value 
)
related

Sets this body to have fixed rotation.

Exceptions
std::out_of_rangeIf given an invalid body identifier.
Note
This also causess the mass data to be reset.
See also
IsFixedRotation.

◆ SetForce()

void SetForce ( World world,
BodyID  id,
Force2  force,
Length2  point 
)
related

Sets the given amount of force at the given point to the given body.

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ SetFrequency()

void SetFrequency ( World world,
JointID  id,
Frequency  value 
)
related

Sets the frequency of the identified joint if it has this property.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ SetFriction()

void SetFriction ( World world,
ContactID  id,
Real  friction 
)
related

Sets the friction value for the identified contact.

Overrides the default friction mixture.

Note
You can call this in "pre-solve" listeners.
This value persists until set or reset.
Warning
Behavior is undefined if given a negative friction value.
Parameters
worldThe world in which the contact is identified in.
idIdentifier of the contact whose friction value should be set.
frictionCo-efficient of friction value of zero or greater.
Exceptions
std::out_of_rangeIf given an invalid contact identifier.

◆ SetImpenetrable() [1/2]

void SetImpenetrable ( World world,
BodyID  id 
)
related

Sets the impenetrable status of the identified body.

Sets that the body should be treated like a bullet for continuous collision detection.

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ SetImpenetrable() [2/2]

void SetImpenetrable ( World world,
BodyID  id,
bool  value 
)
related

Convenience function that sets/unsets the impenetrable status of the identified body.

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ SetJoint() [1/2]

void SetJoint ( World world,
JointID  id,
const Joint def 
)
related

Sets the value of the identified joint.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ SetJoint() [2/2]

template<typename T >
void SetJoint ( World world,
JointID  id,
const T &  value 
)
related

Sets a joint's value from a configuration.

This is a convenience function for allowing limited implicit conversions to joints.

◆ SetLinearDamping()

void SetLinearDamping ( World world,
BodyID  id,
NonNegative< Frequency linearDamping 
)
related

Sets the linear damping of the body.

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ SetLinearOffset()

void SetLinearOffset ( World world,
JointID  id,
Length2  value 
)
related

Sets the target linear offset, in frame A.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ SetLocation()

void SetLocation ( World world,
BodyID  id,
Length2  value 
)
related

Sets the body's location.

This instantly adjusts the body to be at the new location.

Warning
Manipulating a body's location this way can cause non-physical behavior!
Parameters
worldThe world in which the identified body's location should be set.
idIdentifier of body to move.
valueValid world location of the body's local origin. Behavior is undefined if value is invalid.
Exceptions
std::out_of_rangeIf given an invalid body identifier.
See also
GetLocation(const World& world, BodyID id).

◆ SetMassData()

void SetMassData ( World world,
BodyID  id,
const MassData massData 
)
related

Sets the mass properties to override the mass properties of the fixtures.

Note
This changes the center of mass position.
Creating or destroying fixtures can also alter the mass.
This function has no effect if the body isn't dynamic.
Parameters
worldThe world in which the identified body exists.
idIdentifier of the body.
massDatathe mass properties.
Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ SetMaxMotorTorque()

void SetMaxMotorTorque ( World world,
JointID  id,
Torque  value 
)
related

Sets the maximum motor torque.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ SetMotorSpeed()

void SetMotorSpeed ( World world,
JointID  id,
AngularVelocity  value 
)
related

Sets the motor-speed property of the identied joint if it supports it.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.
See also
GetMotorSpeed(const World& world, JointID id)

◆ SetRestitution()

void SetRestitution ( World world,
ContactID  id,
Real  restitution 
)
related

Sets the restitution value for the specified contact.

This override the default restitution mixture.

Note
You can call this in "pre-solve" listeners.
The value persists until you set or reset.

◆ SetSensor()

void SetSensor ( World world,
FixtureID  id,
bool  value 
)
related

Sets whether the fixture is a sensor or not.

Exceptions
std::out_of_rangeIf given an invalid fixture identifier.
See also
IsSensor.

◆ SetSleepingAllowed()

void SetSleepingAllowed ( World world,
BodyID  ,
bool  value 
)
related

Sets whether the identified body is allowed to sleep.

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ SetSubStepping()

void SetSubStepping ( World world,
bool  flag 
)
related

Enables/disables single stepped continuous physics.

Note
This is not normally used. Enabling sub-stepping is meant for testing.
Postcondition
The GetSubStepping() method will return the value this method was called with.
See also
IsStepComplete, GetSubStepping.

◆ SetTangentSpeed()

void SetTangentSpeed ( World world,
ContactID  id,
LinearVelocity  value 
)
related

Sets the desired tangent speed for a conveyor belt behavior.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.

◆ SetTarget()

void SetTarget ( World world,
JointID  id,
Length2  value 
)
related

Sets the target point.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ SetTorque()

void SetTorque ( World world,
BodyID  id,
Torque  torque 
)
related

Sets the given amount of torque to the given body.

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ SetTransform()

void SetTransform ( World world,
BodyID  id,
Length2  location,
Angle  angle 
)
related

Sets the position of the body's origin and rotation.

This instantly adjusts the body to be at the new position and new orientation.

Warning
Manipulating a body's transform can cause non-physical behavior!
Note
Contacts are updated on the next call to World::Step.
Parameters
worldThe world in which the identified body's transform should be set.
idIdentifier of body whose transform is to be set.
locationValid world location of the body's local origin. Behavior is undefined if value is invalid.
angleValid world rotation. Behavior is undefined if value is invalid.
Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ SetTransformation()

void SetTransformation ( World world,
BodyID  id,
Transformation  xfm 
)
related

Sets the transformation of the body.

This instantly adjusts the body to be at the new transformation.

Warning
Manipulating a body's transformation can cause non-physical behavior!
Note
Contacts are updated on the next call to World::Step.
Exceptions
std::out_of_rangeIf given an invalid body identifier.
See also
GetTransformation(const World& world, BodyID id).

◆ SetType()

void SetType ( World world,
BodyID  id,
BodyType  value,
bool  resetMassData = true 
)
related

Sets the type of the given body.

Note
This may alter the body's mass and velocity.
Exceptions
WrongStateif this method is called while the world is locked.
std::out_of_rangeIf given an invalid body identifier.
See also
GetType(const World& world, BodyID id)

◆ SetVelocity() [1/4]

void SetVelocity ( World world,
BodyID  id,
AngularVelocity  value 
)
related

Sets the velocity of the identified body.

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ SetVelocity() [2/4]

void SetVelocity ( World world,
BodyID  id,
const LinearVelocity2 value 
)
related

Sets the velocity of the identified body.

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ SetVelocity() [3/4]

void SetVelocity ( World world,
BodyID  id,
const Velocity value 
)
related

Sets the body's velocity (linear and angular velocity).

Note
This method does nothing if this body is not speedable.
A non-zero velocity will awaken this body.
Exceptions
std::out_of_rangeIf given an invalid body identifier.
See also
GetVelocity(BodyID), SetAwake, SetUnderActiveTime.

◆ SetVelocity() [4/4]

void SetVelocity ( World world,
BodyID  id,
const Velocity value 
)
related

Sets the body's velocity (linear and angular velocity).

Note
This method does nothing if this body is not speedable.
A non-zero velocity will awaken this body.
Exceptions
std::out_of_rangeIf given an invalid body identifier.
See also
GetVelocity.

◆ ShiftOrigin() [1/2]

bool ShiftOrigin ( World world,
JointID  id,
Length2  value 
)
related

Shifts the origin of the identified joint.

Note
This only effects joints having points in world coordinates.
Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ ShiftOrigin() [2/2]

void ShiftOrigin ( World world,
Length2  newOrigin 
)
related

Shifts the world origin.

Note
Useful for large worlds.
The body shift formula is: position -= newOrigin.
Postcondition
The "origin" of this world's bodies, joints, and the board-phase dynamic tree have been translated per the shift amount and direction.
Parameters
worldThe world whose origin should be shifted.
newOriginthe new origin with respect to the old origin
Exceptions
WrongStateif this method is called while the world is locked.

◆ Step()

StepStats Step ( World world,
Time  delta,
TimestepIters  velocityIterations = 8,
TimestepIters  positionIterations = 3 
)
related

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.
deltaTime to simulate as a delta from the current state. 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.

◆ UnsetAwake() [1/2]

void UnsetAwake ( World world,
BodyID  id 
)
related

Sleeps the identified body.

Note
This sleeps any associated contacts whose other body is also asleep.
Exceptions
std::out_of_rangeIf given an invalid body identifier.
See also
IsAwake(const World& world, BodyID id), SetAwake(World& world, BodyID id).

◆ UnsetAwake() [2/2]

void UnsetAwake ( World world,
BodyID  id 
)
related

Sleeps the identified body.

Exceptions
std::out_of_rangeIf given an invalid body identifier.
See also
IsAwake, SetAwake.

◆ UnsetEnabled()

void UnsetEnabled ( World world,
ContactID  id 
)
related

Unsets the enabled status of the identified contact.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.

◆ UnsetImpenetrable()

void UnsetImpenetrable ( World world,
BodyID  id 
)
related

Unsets the impenetrable status of the identified body.

Exceptions
std::out_of_rangeIf given an invalid body identifier.

Member Data Documentation

◆ m_impl


The documentation for this class was generated from the following files:
playrho::BodyType::Static
@ Static
Static body type.
playrho::d2::World::World
World(const WorldConf &def=GetDefaultWorldConf())
Constructs a world object.
Definition: WorldSpecial.cpp:35