PlayRho  2.0.0
An interactive physics engine & library.
playrho::d2 Namespace Reference

Namespaces

 detail
 
 part
 

Classes

class  AabbTreeWorld
 An AABB dynamic-tree based world implementation. More...
 
struct  Acceleration
 2-D acceleration related data structure. More...
 
struct  BaseShapeConf
 Base configuration for initializing shapes. More...
 
class  Body
 A "body" physical entity. More...
 
struct  BodyConf
 Configuration for a body. More...
 
class  BodyConstraint
 Constraint for a body. More...
 
struct  ChainShapeConf
 Chain shape configuration. More...
 
class  ContactImpulsesList
 
class  ConvexHull
 Convex hull. More...
 
struct  DiskShapeConf
 Disk shape configuration. More...
 
struct  DistanceConf
 Distance Configuration. More...
 
struct  DistanceJointConf
 Distance joint definition. More...
 
struct  DistanceOutput
 Distance Output. More...
 
class  DistanceProxy
 Distance Proxy. More...
 
class  DynamicTree
 A dynamic AABB tree broad-phase. More...
 
struct  EdgeShapeConf
 Edge shape configuration. More...
 
struct  FrictionJointConf
 Friction joint definition. More...
 
struct  GearJointConf
 Gear joint definition. More...
 
class  Joint
 A joint-like constraint on one or more bodies. More...
 
struct  JointBuilder
 Joint builder definition structure. More...
 
struct  JointConf
 Base joint definition class. More...
 
class  Manifold
 A collision response oriented description of the intersection of two convex shapes. More...
 
struct  MotorJointConf
 Motor joint definition. More...
 
struct  MultiShapeConf
 The "multi-shape" shape configuration. More...
 
class  NgonWithFwdNormals
 N-gon of vertices with counter-clockwise "forward" normals. More...
 
class  NgonWithFwdNormals< static_cast< std::size_t >(-1)>
 N-gon of runtime-arbitray vertices with counter-clockwise "forward" normals. More...
 
struct  PointStates
 Point states. More...
 
struct  PolygonShapeConf
 An n-vertex convex polygon shaped part eligible for use with a Shape. More...
 
struct  Position
 2-D positional data structure. More...
 
struct  PositionConstraint
 The per-contact position constraint data structure. More...
 
struct  PositionSolution
 Solution for position constraint. More...
 
struct  PrismaticJointConf
 Prismatic joint definition. More...
 
struct  PulleyJointConf
 Pulley joint definition. More...
 
struct  RayCastHit
 Ray-cast hit data. More...
 
struct  RevoluteJointConf
 Revolute joint definition. More...
 
struct  RopeJointConf
 Rope joint definition. More...
 
struct  SeparationScenarioFaceA
 Face A separation scenario. More...
 
struct  SeparationScenarioFaceB
 Face B separation scenario. More...
 
struct  SeparationScenarioPoints
 Points separation scenario. More...
 
class  Shape
 Shape. More...
 
struct  ShapeBuilder
 Builder configuration structure. More...
 
struct  ShapeConf
 Shape configuration structure. More...
 
class  Simplex
 An encapsulation of a point, line segment, or triangle. More...
 
class  SimplexEdge
 Simplex edge. More...
 
struct  Sweep
 Description of a "sweep" of motion in 2-D space. More...
 
struct  TargetJointConf
 Target joint definition. More...
 
struct  Transformation
 Describes a geometric transformation. More...
 
class  UnitVec
 2-D unit vector. More...
 
struct  Velocity
 2-D velocity related data structure. More...
 
class  VelocityConstraint
 The per-contact velocity constraint data structure. More...
 
class  VertexSet
 Vertex Set. More...
 
struct  WeldJointConf
 Weld joint definition. More...
 
struct  WheelJointConf
 Wheel joint definition. More...
 
class  World
 Definition of an independent and simulatable "world". More...
 
struct  WorldConf
 World configuration data. More...
 
class  WorldManifold
 Essentially a Manifold expressed in world coordinate terms. More...
 

Typedefs

using AABB = ::playrho::detail::AABB< 2 >
 2-Dimensional Axis Aligned Bounding Box.
 
using BodyConstraints = std::vector< BodyConstraint, pmr::polymorphic_allocator< BodyConstraint > >
 Collection of body constraints.
 
using BodyContactIDs = std::vector< std::tuple< ContactKey, ContactID > >
 Container type for Body associated contact information.
 
using BodyIDs = std::vector< BodyID >
 Body IDs container type.
 
using BodyJointIDs = std::vector< std::pair< BodyID, JointID > >
 Body joint IDs container type.
 
using BodyShapeIDs = std::vector< std::pair< BodyID, ShapeID > >
 Body shape IDs container type.
 
using ContactImpulsesFunction = std::function< void(ContactID, const ContactImpulsesList &, unsigned)>
 Contact-impulses function.
 
using ContactManifoldFunction = std::function< void(ContactID, const Manifold &)>
 Contact-manifolds function.
 
using DynamicTreeRayCastCB = std::function< Real(BodyID body, ShapeID shape, ChildCounter child, const RayCastInput &input)>
 Ray cast callback function. More...
 
using DynamicTreeSizeCB = std::function< DynamicTreeOpcode(DynamicTree::Size)>
 Query callback type.
 
using JointIDs = std::vector< JointID >
 Joint IDs container type. More...
 
using KeyedContactIDs = std::vector< KeyedContactID >
 Keyed contact IDs container type.
 
using LengthIndices = ::playrho::detail::LengthIndices< 2 >
 Length and vertex counter array of indices for 2-D space.
 
using MassData = ::playrho::detail::MassData< 2 >
 Mass data alias for 2-D objects.
 
using PositionConstraints = std::vector< PositionConstraint, pmr::polymorphic_allocator< PositionConstraint > >
 Collection of position constraints.
 
using ProxyIDs = std::vector< DynamicTree::Size >
 Proxy container type alias.
 
using QueryShapeCallback = std::function< bool(BodyID body, ShapeID shape, ChildCounter child)>
 Query AABB for fixtures callback function type. More...
 
using RayCastInput = playrho::detail::RayCastInput< 2 >
 Ray cast input data for 2-dimensions.
 
using RayCastOutput = std::optional< RayCastHit >
 Ray cast output. More...
 
using SeparationInfo = ::playrho::detail::SeparationInfo< 2 >
 Separation information alias for 2-D space.
 
using SeparationScenario = std::variant< SeparationScenarioPoints, SeparationScenarioFaceA, SeparationScenarioFaceB >
 Separation scenario.
 
using ShapeRayCastCB = std::function< RayCastOpcode(BodyID body, ShapeID shape, ChildCounter child, const Length2 &point, UnitVec normal)>
 Ray cast callback function signature.
 
using SimplexEdges = ArrayList< SimplexEdge, MaxSimplexEdges, std::remove_const_t< decltype(MaxSimplexEdges)> >
 Simplex edge collection.
 
using VelocityConstraints = std::vector< VelocityConstraint, pmr::polymorphic_allocator< VelocityConstraint > >
 Collection of velocity constraints.
 
using VelocityPair = std::pair< Velocity, Velocity >
 Velocity pair.
 

Enumerations

enum class  DynamicTreeOpcode { End , Continue }
 Opcodes for dynamic tree callbacks.
 

Functions

void Advance (Body &body, ZeroToUnderOneFF< Real > value) noexcept
 
void Advance0 (Body &body, ZeroToUnderOneFF< Real > value) noexcept
 Calls the body sweep's Advance0 function to advance to the given value. More...
 
Sweep Advance0 (const Sweep &sweep, ZeroToUnderOneFF< Real > alpha) noexcept
 Advances the sweep by a factor of the difference between the given time alpha and the sweep's alpha 0. More...
 
void ApplyAngularImpulse (Body &body, AngularMomentum impulse) noexcept
 Applies an angular impulse. More...
 
void ApplyAngularImpulse (World &world, BodyID id, AngularMomentum impulse)
 Applies an angular impulse. More...
 
void ApplyForce (World &world, BodyID id, const Force2 &force, const Length2 &point)
 Apply a force at a world point. More...
 
void ApplyForceToCenter (World &world, BodyID id, const Force2 &force)
 Applies a force to the center of mass of the given body. More...
 
void ApplyLinearImpulse (Body &body, const Momentum2 &impulse, const Length2 &point) noexcept
 Applies an impulse at a point. More...
 
void ApplyLinearImpulse (World &world, BodyID id, const Momentum2 &impulse, const Length2 &point)
 Applies an impulse at a point. More...
 
void ApplyTorque (World &world, BodyID id, Torque torque)
 Applies a torque. More...
 
BodyConstraintAt (const Span< BodyConstraint > &container, BodyID key)
 Provides referenced access to the identified element of the given container.
 
void Attach (AabbTreeWorld &world, BodyID id, ShapeID shapeID)
 Associates a validly identified shape with the validly identified body. More...
 
void Attach (World &world, BodyID id, const Shape &shape, bool resetMassData=true)
 Creates the shape within the world and then associates it with the validly identified body. More...
 
void Attach (World &world, BodyID id, ShapeID shapeID, bool resetMassData=true)
 Associates a validly identified shape with the validly identified body. More...
 
bool Awaken (Body &body) noexcept
 Awakens the body if it's asleep. More...
 
BodyCounter Awaken (World &world)
 Awakens all of the "speedable" bodies in the given world. More...
 
bool Awaken (World &world, BodyID id)
 Awakens the body if it's asleep and "speedable". More...
 
Acceleration CalcGravitationalAcceleration (const World &world, BodyID id)
 Calculates the gravitationally associated acceleration for the given body within its world. More...
 
Length2 CalcSearchDirection (const SimplexEdges &simplexEdges) noexcept
 Calculates the "search direction" for the given simplex edge list. More...
 
Position Cap (Position pos, const ConstraintSolverConf &conf)
 Caps the given position by the amounts specified in the given configuration.
 
Velocity Cap (Velocity velocity, Time h, const MovementConf &conf) noexcept
 Caps velocity. More...
 
void Clear (World &world) noexcept
 Clears the given world. More...
 
void ClearForces (World &world)
 Clears forces. More...
 
Manifold CollideShapes (const DistanceProxy &shapeA, const Transformation &xfA, const DistanceProxy &shapeB, const Transformation &xfB, const Manifold::Conf &conf=GetDefaultManifoldConf())
 Calculates the relevant collision manifold. More...
 
AABB ComputeAABB (const DistanceProxy &proxy, const Transformation &xf) noexcept
 Computes the AABB. More...
 
AABB ComputeAABB (const DistanceProxy &proxy, const Transformation &xfm0, const Transformation &xfm1) noexcept
 Computes the AABB. More...
 
AABB ComputeAABB (const Shape &shape, const Transformation &xf)
 Computes the AABB for the given shape with the given transformation.
 
AABB ComputeAABB (const World &world, BodyID bodyID, ShapeID shapeID)
 Computes the AABB for the identified shape relative to the identified body within the given world. More...
 
AABB ComputeAABB (const World &world, BodyID id)
 Computes the AABB for the identified body within the given world. More...
 
DynamicTree::Height ComputeHeight (const DynamicTree &tree) noexcept
 Computes the height of the given dynamic tree.
 
DynamicTree::Height ComputeHeight (const DynamicTree &tree, DynamicTree::Size index) noexcept
 Computes the height of the tree from a given node. More...
 
AABB ComputeIntersectingAABB (const World &world, BodyID bA, ShapeID sA, ChildCounter iA, BodyID bB, ShapeID sB, ChildCounter iB)
 Computes the intersecting AABB for the given pair of body-shape-index values. More...
 
AABB ComputeIntersectingAABB (const World &world, const Contact &contact)
 Computes the intersecting AABB for the given contact. More...
 
MassData ComputeMassData (const World &world, BodyID id)
 Computes the identified body's mass data. More...
 
MassData ComputeMassData (const World &world, const Span< const ShapeID > &ids)
 Computes the mass data total of the identified shapes. More...
 
Real ComputePerimeterRatio (const DynamicTree &tree) noexcept
 Gets the ratio of the sum of the perimeters of nodes to the root perimeter. More...
 
Length ComputeTotalPerimeter (const DynamicTree &tree) noexcept
 Gets the sum of the perimeters of nodes. More...
 
BodyID CreateBody (AabbTreeWorld &world, const BodyConf &def)
 Creates a body within the world that's a copy of the given one.
 
BodyID CreateBody (World &world, const Body &body=Body{}, bool resetMassData=true)
 Creates a rigid body within the world that's a copy of the given one. More...
 
BodyID CreateBody (World &world, const BodyConf &def, bool resetMassData=true)
 Creates a rigid body with the given configuration. More...
 
JointID CreateJoint (World &world, const Joint &def)
 Creates a new joint within the given world. More...
 
template<typename T >
JointID CreateJoint (World &world, const T &value)
 Creates a new joint from a configuration. More...
 
ShapeID CreateShape (World &world, const Shape &def)
 Creates an identifiable copy of the given shape within the specified world. More...
 
template<typename T >
auto CreateShape (World &world, const T &shapeConf) -> decltype(CreateShape(world, Shape{shapeConf}))
 Creates a shape within the specified world using a configuration of the shape. More...
 
void Destroy (World &world, BodyID id)
 Destroys the identified body. More...
 
void Destroy (World &world, JointID id)
 Destroys the identified joint. More...
 
void Destroy (World &world, ShapeID id)
 Destroys the identified shape. More...
 
bool Detach (AabbTreeWorld &world, BodyID id, ShapeID shapeID)
 Disassociates a validly identified shape from the validly identified body. More...
 
bool Detach (World &world, BodyID id, bool resetMassData=true)
 Disassociates all of the associated shape from the validly identified body. More...
 
bool Detach (World &world, BodyID id, ShapeID shapeID, bool resetMassData=true)
 Disassociates a validly identified shape from the validly identified body. More...
 
DistanceOutput Distance (const DistanceProxy &proxyA, const Transformation &transformA, const DistanceProxy &proxyB, const Transformation &transformB, DistanceConf conf=DistanceConf{})
 Determines the closest points between two shapes using an iterative method. More...
 
void EnableLimit (Joint &object, bool value)
 Enables the specified joint's limit property if it supports one. More...
 
template<typename T >
constexpr auto EnableLimit (T &conf, bool v) noexcept -> decltype(std::declval< T >().UseEnableLimit(bool{}))
 Enables or disables the limit based on the given value.
 
void EnableLimit (World &world, JointID id, bool value)
 Sets whether the identified joint's limit is enabled or not. More...
 
void EnableMotor (Joint &object, bool value)
 Enables the specified joint's motor property if it supports one. More...
 
template<typename T >
constexpr auto EnableMotor (T &conf, bool v) noexcept -> decltype(std::declval< T >().UseEnableMotor(bool{}))
 Enables or disables the motor property of the given object.
 
void EnableMotor (World &world, JointID id, bool value)
 
Length Evaluate (const SeparationScenario &scenario, const DistanceProxy &proxyA, const Transformation &xfA, const DistanceProxy &proxyB, const Transformation &xfB, IndexPair indexPair)
 
BodyID FindClosestBody (const World &world, const Length2 &location)
 Finds body in given world that's closest to the given location. More...
 
auto FindIndex (const DynamicTree &tree, const Contactable &c) noexcept -> DynamicTree::Size
 Finds index of node matching given contactble using a linear search. More...
 
std::size_t FindLowestRightMostVertex (Span< const Length2 > vertices) noexcept
 Finds the index of the lowest right most vertex in the given collection. More...
 
LengthIndexPair FindMinSeparation (const SeparationScenario &scenario, const DistanceProxy &proxyA, const Transformation &xfA, const DistanceProxy &proxyB, const Transformation &xfB)
 Finds the minimum separation. More...
 
template<std::size_t I>
constexpr UnitVec::value_type get (const UnitVec &v) noexcept
 Gets the specified element of the given collection.
 
template<>
constexpr UnitVec::value_type get< 0 > (const UnitVec &v) noexcept
 Gets element 0 of the given collection.
 
template<>
constexpr UnitVec::value_type get< 1 > (const UnitVec &v) noexcept
 Gets element 1 of the given collection.
 
AABB GetAABB (const DynamicTree &tree) noexcept
 Gets the AABB for the given dynamic tree. More...
 
constexpr AABB GetAABB (const DynamicTree::TreeNode &node) noexcept
 Gets the AABB of the given dynamic tree node. More...
 
AABB GetAABB (const playrho::detail::RayCastInput< 2 > &input) noexcept
 Gets the AABB for the given ray cast input data. <2>
 
Acceleration GetAcceleration (const Body &body) noexcept
 Gets the given body's acceleration. More...
 
Acceleration GetAcceleration (const World &world, BodyID id)
 Gets the acceleration of the identified body. More...
 
Length2 GetAnchorA (const World &world, JointID id)
 
Length2 GetAnchorB (const World &world, JointID id)
 
Angle GetAngle (const Body &body) noexcept
 Gets the body's angle. More...
 
constexpr auto GetAngle (const BodyConf &conf) noexcept -> Angle
 Gets the angle of the given configuration.
 
Angle GetAngle (const Transformation &value)
 Gets the angle of the given transformation.
 
Angle GetAngle (const UnitVec &value)
 Gets the angle of the given unit vector.
 
Angle GetAngle (const World &world, BodyID id)
 Gets the angle of the identified body. More...
 
Angle GetAngle (const World &world, const RevoluteJointConf &conf)
 Gets the current angle of the given configuration in the given world. More...
 
Angle GetAngle (const World &world, JointID id)
 Gets the angle property of the identified joint if it has it. More...
 
AngularAcceleration GetAngularAcceleration (const Body &body) noexcept
 Gets this body's angular acceleration. More...
 
AngularAcceleration GetAngularAcceleration (const World &world, BodyID id)
 Gets this body's angular acceleration. More...
 
NonNegative< FrequencyGetAngularDamping (const Body &body) noexcept
 Gets the angular damping of the body. More...
 
Frequency GetAngularDamping (const World &world, BodyID id)
 Gets the angular damping of the body. More...
 
constexpr auto GetAngularError (const MotorJointConf &object) noexcept
 Free function for getting the angular error value of the given configuration.
 
Angle GetAngularLowerLimit (const Joint &object)
 
constexpr Angle GetAngularLowerLimit (const RevoluteJointConf &conf) noexcept
 Free function for getting the angular lower limit value of the given configuration.
 
Angle GetAngularLowerLimit (const World &world, JointID id)
 
RotInertia GetAngularMass (const Joint &object)
 Gets the given joint's angular mass. More...
 
template<typename T >
constexpr auto GetAngularMass (const T &conf) noexcept -> decltype(std::declval< T >().angularMass)
 Gets the angular mass property of the given object.
 
RotInertia GetAngularMass (const World &world, JointID id)
 Gets the computed angular rotational inertia used by the joint. More...
 
AngularMomentum GetAngularMotorImpulse (const Joint &object)
 Gets the angular motor impulse of the joint if it has this property. More...
 
template<typename T >
constexpr auto GetAngularMotorImpulse (const T &conf) noexcept -> decltype(std::declval< T >().angularMotorImpulse)
 Gets the angular motor impulse property of the given object.
 
AngularMomentum GetAngularMotorImpulse (const World &world, JointID id)
 Gets the angular motor impulse of the identified joint if it has this property. More...
 
Angle GetAngularOffset (const Joint &object)
 Gets the angular offset property of the specified joint if its type has one. More...
 
constexpr auto GetAngularOffset (const MotorJointConf &object) noexcept
 Free function for getting the angular offset value of the given configuration.
 
template<typename T >
constexpr auto GetAngularOffset (const T &conf) noexcept -> decltype(std::declval< T >().angularOffset)
 Gets the angular offset property of the given object.
 
Angle GetAngularOffset (const World &world, JointID id)
 Gets the target angular offset. More...
 
constexpr AngularMomentum GetAngularReaction (const DistanceJointConf &) noexcept
 Gets the current angular reaction for the given configuration.
 
constexpr AngularMomentum GetAngularReaction (const FrictionJointConf &object) noexcept
 Gets the current angular reaction for the given configuration.
 
constexpr AngularMomentum GetAngularReaction (const GearJointConf &object)
 Gets the current angular reaction for the given configuration.
 
AngularMomentum GetAngularReaction (const Joint &object)
 
AngularMomentum GetAngularReaction (const PrismaticJointConf &conf)
 Gets the current angular reaction of the given configuration.
 
constexpr AngularMomentum GetAngularReaction (const PulleyJointConf &) noexcept
 Gets the current angular reaction of the given configuration.
 
constexpr AngularMomentum GetAngularReaction (const RevoluteJointConf &conf) noexcept
 Gets the current angular reaction of the given configuration.
 
constexpr AngularMomentum GetAngularReaction (const RopeJointConf &) noexcept
 Gets the current angular reaction of the given configuration.
 
template<typename T >
constexpr auto GetAngularReaction (const T &conf) noexcept -> decltype(std::declval< T >().angularImpulse)
 Gets the angular reaction property of the given object.
 
constexpr AngularMomentum GetAngularReaction (const TargetJointConf &)
 Gets the current angular reaction of the given configuration.
 
constexpr AngularMomentum GetAngularReaction (const WeldJointConf &object) noexcept
 Gets the current angular reaction of the given configuration.
 
AngularMomentum GetAngularReaction (const World &world, JointID id)
 Get the angular reaction on body-B for the identified joint. More...
 
Angle GetAngularUpperLimit (const Joint &object)
 Gets the upper joint limit. More...
 
constexpr Angle GetAngularUpperLimit (const RevoluteJointConf &conf) noexcept
 Free function for getting the angular upper limit value of the given configuration.
 
Angle GetAngularUpperLimit (const World &world, JointID id)
 
AngularVelocity GetAngularVelocity (const Body &body) noexcept
 Gets the angular velocity. More...
 
AngularVelocity GetAngularVelocity (const World &world, BodyID id)
 Gets the angular velocity. More...
 
AngularVelocity GetAngularVelocity (const World &world, const RevoluteJointConf &conf)
 Gets the current angular velocity of the given configuration. More...
 
AngularVelocity GetAngularVelocity (const World &world, const WheelJointConf &conf)
 Gets the angular velocity for the given configuration within the specified world. More...
 
AngularVelocity GetAngularVelocity (const World &world, JointID id)
 Gets the angular velocity of the identified joint if it has this property. More...
 
ShapeCounter GetAssociationCount (const World &world)
 Gets the count of body-shape associations in the given world. More...
 
BodyCounter GetAwakeCount (const World &world)
 Gets the count of awake bodies in the given world. More...
 
std::vector< BodyIDGetBodies (const World &world)
 Gets the valid world body identifiers container for this constant world. More...
 
std::vector< BodyIDGetBodiesForProxies (const World &world)
 Gets the bodies-for-proxies container for this world. More...
 
Body GetBody (const World &world, BodyID id)
 Gets the state of the identified body. More...
 
BodyID GetBodyA (const Joint &object) noexcept
 Gets the first body attached to this joint.
 
constexpr BodyID GetBodyA (const JointConf &object) noexcept
 Gets the first body attached to this joint.
 
BodyID GetBodyA (const World &world, ContactID id)
 Gets the body-A of the identified contact if it has one. More...
 
BodyID GetBodyA (const World &world, JointID id)
 Gets the identifier of body-A of the identified joint. More...
 
BodyID GetBodyB (const Joint &object) noexcept
 Gets the second body attached to this joint.
 
constexpr BodyID GetBodyB (const JointConf &object) noexcept
 Gets the second body attached to this joint.
 
BodyID GetBodyB (const World &world, ContactID id)
 Gets the body-B of the identified contact if it has one. More...
 
BodyID GetBodyB (const World &world, JointID id)
 Gets the identifier of body-B of the identified joint. More...
 
BodyConf GetBodyConf (const Body &body)
 Gets the body definition for the given body. More...
 
BodyConstraint GetBodyConstraint (const Body &body, Time time, const MovementConf &conf) noexcept
 Gets the BodyConstraint based on the given parameters.
 
BodyCounter GetBodyCount (const World &world) noexcept
 Gets the body count in the given world. More...
 
BodyCounter GetBodyRange (const World &world) noexcept
 Gets the extent of the currently valid body range. More...
 
Force2 GetCentripetalForce (const World &world, BodyID id, const Length2 &axis)
 Gets the centripetal force necessary to put the body into an orbit having the given radius. More...
 
ChainShapeConf GetChainShapeConf (const AABB &arg)
 Gets an enclosing chain shape configuration for the given axis aligned box.
 
ChainShapeConf GetChainShapeConf (const Length2 &dimensions)
 Gets an enclosing chain shape configuration for an axis aligned rectangle of the given dimensions (width and height).
 
ChainShapeConf GetChainShapeConf (Length dimension)
 Gets an enclosing chain shape configuration for an axis aligned square of the given dimension.
 
DistanceProxy GetChild (const ChainShapeConf &arg, ChildCounter index)
 Gets the "child" shape for a given chain shape configuration.
 
DistanceProxy GetChild (const DiskShapeConf &arg, ChildCounter index)
 Gets the "child" of the given disk shape configuration.
 
DistanceProxy GetChild (const EdgeShapeConf &arg, ChildCounter index)
 Gets the "child" shape for the given shape configuration.
 
DistanceProxy GetChild (const MultiShapeConf &arg, ChildCounter index)
 Gets the "child" shape for the given shape configuration.
 
DistanceProxy GetChild (const PolygonShapeConf &arg, ChildCounter index)
 Gets the "child" shape for the given shape configuration.
 
DistanceProxy GetChild (const Shape &shape, ChildCounter index)
 Gets the "child" for the given index. More...
 
DistanceProxy GetChild (Shape &&shape, ChildCounter index)=delete
 Getting the "child" for a temporary is deleted to prevent dangling references.
 
ChildCounter GetChildCount (const ChainShapeConf &arg) noexcept
 Gets the child count for a given chain shape configuration.
 
constexpr ChildCounter GetChildCount (const DiskShapeConf &) noexcept
 Gets the "child" count of the given disk shape configuration.
 
constexpr ChildCounter GetChildCount (const EdgeShapeConf &) noexcept
 Gets the "child" count for the given shape configuration. More...
 
ChildCounter GetChildCount (const MultiShapeConf &arg) noexcept
 Gets the "child" count for the given shape configuration.
 
constexpr ChildCounter GetChildCount (const PolygonShapeConf &) noexcept
 Gets the "child" count for the given shape configuration. More...
 
ChildCounter GetChildCount (const Shape &shape) noexcept
 Gets the number of child primitives of the shape. More...
 
ChildCounter GetChildIndexA (const World &world, ContactID id)
 Gets the child primitive index A for the identified contact. More...
 
ChildCounter GetChildIndexB (const World &world, ContactID id)
 Gets the child primitive index B for the identified contact. More...
 
constexpr Length2 GetClosestPoint (const Simplex &simplex)
 Gets the "closest point".
 
bool GetCollideConnected (const Joint &object) noexcept
 Gets collide connected. More...
 
constexpr bool GetCollideConnected (const JointConf &object) noexcept
 Gets whether attached bodies should collide or not.
 
bool GetCollideConnected (const World &world, JointID id)
 Gets collide connected for the specified joint. More...
 
constexpr auto GetConstant (const GearJointConf &object) noexcept
 Free function for getting the constant value of the given configuration.
 
Contact GetContact (const World &world, ContactID id)
 Gets the identified contact. More...
 
ContactCounter GetContactCount (const World &world) noexcept
 Gets the count of contacts in the given world. More...
 
ContactImpulsesList GetContactImpulses (const VelocityConstraint &vc)
 Gets the contact impulses for the given velocity constraint.
 
ContactCounter GetContactRange (const World &world) noexcept
 Gets the extent of the currently valid contact range. More...
 
LinearVelocity2 GetContactRelVelocity (const Velocity &velA, const Length2 &relA, const Velocity &velB, const Length2 &relB) noexcept
 Gets the contact relative velocity. More...
 
std::vector< KeyedContactIDGetContacts (const World &world)
 Gets the contacts identified within the given world. More...
 
std::vector< std::tuple< ContactKey, ContactID > > GetContacts (const World &world, BodyID id)
 Gets the container of contacts attached to the identified body. More...
 
std::vector< Length2GetConvexHullAsVector (Span< const Length2 > vertices)
 Gets the convex hull for the given collection of vertices as a vector. More...
 
constexpr auto GetCorrectionFactor (const MotorJointConf &object) noexcept
 Free function for getting the correction factor value of the given configuration.
 
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...
 
Real GetDampingRatio (const Joint &object)
 Gets the given joint's damping ratio property if it has one. More...
 
template<typename T >
constexpr auto GetDampingRatio (const T &conf) noexcept -> decltype(std::declval< T >().dampingRatio)
 Gets the damping ratio property of the given object.
 
Real GetDampingRatio (const World &world, JointID id)
 Gets the damping ratio associated with the identified joint if it has one. More...
 
const void * GetData (const Shape &shape) noexcept
 Gets a pointer to the underlying data. More...
 
constexpr BodyConf GetDefaultBodyConf () noexcept
 Gets the default body definition.
 
NonNegativeFF< RealGetDefaultFriction (const Shape &a, const Shape &b)
 Gets the default friction amount for the given shapes.
 
Real GetDefaultFriction (const World &world, ContactID id)
 Gets the default friction amount for the identified contact. More...
 
constexpr Manifold::Conf GetDefaultManifoldConf () noexcept
 Gets the default manifold configuration.
 
Real GetDefaultRestitution (const Shape &a, const Shape &b)
 Gets the default restitution amount for the given shapes.
 
Real GetDefaultRestitution (const World &world, ContactID id)
 Gets the default restitution amount for the identified contact. More...
 
constexpr Length2 GetDelta (PairLength2 arg) noexcept
 Gets the delta to go from the first element to the second.
 
constexpr NonNegative< AreaDensityGetDensity (const BaseShapeConf &arg) noexcept
 Gets the density of the given shape configuration.
 
NonNegative< AreaDensityGetDensity (const Shape &shape) noexcept
 Gets the density of the given shape. More...
 
NonNegative< AreaDensityGetDensity (const World &world, ShapeID id)
 Gets the density of this shape. More...
 
constexpr UnitVec GetDirection (const Transformation &value) noexcept
 Gets the directional information from the given transformation.
 
DistanceConf GetDistanceConf (const StepConf &conf) noexcept
 Gets the distance configuration for the given step configuration.
 
DistanceConf GetDistanceConf (const ToiConf &conf) noexcept
 Gets the distance configuration for the given time of impact configuration.
 
DistanceJointConf GetDistanceJointConf (const Joint &joint)
 Gets the definition data for the given joint. More...
 
DistanceJointConf GetDistanceJointConf (const World &world, BodyID bodyA, BodyID bodyB, const Length2 &anchorA=Length2{}, const Length2 &anchorB=Length2{})
 Gets the configuration for a joint with the given parameters. More...
 
InvMass GetEffectiveInvMass (const InvRotInertia &invRotI, const Length2 &p, const UnitVec &q)
 Gets the "effective" inverse mass.
 
Mass22 GetEffectiveMassMatrix (const TargetJointConf &object, const BodyConstraint &body) noexcept
 Gets the effective mass matrix for the given configuration and body information.
 
constexpr Filter GetFilter (const BaseShapeConf &arg) noexcept
 Gets the filter of the given shape configuration.
 
Filter GetFilter (const Shape &shape) noexcept
 Gets the filter value for the given shape. More...
 
Filter GetFilterData (const World &world, ShapeID id)
 Gets the filter data for the identified shape. More...
 
Force2 GetForce (const Body &body) noexcept
 Gets the net force that the given body is currently experiencing.
 
Frequency GetFrequency (const Joint &object)
 Gets the frequency of the joint if it has this property. More...
 
template<typename T >
constexpr auto GetFrequency (const T &conf) noexcept -> decltype(std::declval< T >().frequency)
 Gets the frequency property of the given object.
 
Frequency GetFrequency (const World &world, JointID id)
 Gets the frequency of the identified joint if it has this property. More...
 
constexpr NonNegativeFF< RealGetFriction (const BaseShapeConf &arg) noexcept
 Gets the friction of the given shape.
 
NonNegativeFF< RealGetFriction (const Shape &shape) noexcept
 Gets the coefficient of friction. More...
 
NonNegativeFF< RealGetFriction (const World &world, ContactID id)
 Gets the friction used with the identified contact. More...
 
NonNegativeFF< RealGetFriction (const World &world, ShapeID id)
 Gets the coefficient of friction of the specified shape. More...
 
FrictionJointConf GetFrictionJointConf (const Joint &joint)
 Gets the definition data for the given joint. More...
 
FrictionJointConf GetFrictionJointConf (const World &world, BodyID bodyA, BodyID bodyB, const Length2 &anchor)
 Gets the confguration for the given parameters. More...
 
template<std::size_t N>
std::array< UnitVec, N > GetFwdNormalsArray (const std::array< Length2, N > &vertices)
 Gets forward normals for the given vertices.
 
template<class T , T... ints>
std::array< UnitVec, sizeof...(ints)> GetFwdNormalsArray (const std::array< Length2, sizeof...(ints)> &vertices, std::integer_sequence< T, ints... > int_seq)
 Gets forward normals for the given vertices.
 
std::vector< UnitVecGetFwdNormalsVector (const std::vector< Length2 > &vertices)
 Gets the forward normals for the given container of vertices.
 
constexpr UnitVec GetFwdPerpendicular (const UnitVec &vector) noexcept
 Gets a vector clockwise (forward-clockwise) perpendicular to the given vector. More...
 
GearJointConf GetGearJointConf (const Joint &joint)
 Gets the definition data for the given joint. More...
 
GearJointConf GetGearJointConf (const World &world, JointID id1, JointID id2, Real ratio=Real{1})
 Gets the configuration for the given parameters. More...
 
Length2 GetGroundAnchorA (const Joint &object)
 
template<typename T >
constexpr auto GetGroundAnchorA (const T &conf) noexcept -> decltype(std::declval< T >().groundAnchorA)
 Gets the ground anchor A property of the given object.
 
Length2 GetGroundAnchorA (const World &world, JointID id)
 
Length2 GetGroundAnchorB (const Joint &object)
 
template<typename T >
constexpr auto GetGroundAnchorB (const T &conf) noexcept -> decltype(std::declval< T >().groundAnchorB)
 Gets the ground anchor B property of the given object.
 
Length2 GetGroundAnchorB (const World &world, JointID id)
 
DynamicTree::Height GetHeight (const DynamicTree &tree) noexcept
 Gets the height of the binary tree. More...
 
IndexPair3 GetIndexPairs (const SimplexEdges &collection) noexcept
 Gets index pairs for the given edges collection.
 
Frequency GetInvDeltaTime (const World &world) noexcept
 Gets the inverse delta time. More...
 
NonNegativeFF< InvMassGetInvMass (const Body &body) noexcept
 Gets the inverse total mass of the body. More...
 
InvMass GetInvMass (const World &world, BodyID id)
 Gets the inverse total mass of the body. More...
 
NonNegativeFF< InvRotInertiaGetInvRotInertia (const Body &body) noexcept
 Gets the inverse rotational inertia of the body. More...
 
InvRotInertia GetInvRotInertia (const World &world, BodyID id)
 Gets the inverse rotational inertia of the body. More...
 
Joint GetJoint (const World &world, JointID id)
 Gets the value of the identified joint. More...
 
JointCounter GetJointCount (const World &world)
 
JointCounter GetJointRange (const World &world) noexcept
 Gets the extent of the currently valid joint range. More...
 
std::vector< JointIDGetJoints (const World &world)
 Gets the joints of the specified world. More...
 
std::vector< std::pair< BodyID, JointID > > GetJoints (const World &world, BodyID id)
 Gets the container of valid joints attached to the identified body. More...
 
Length GetJointTranslation (const World &world, JointID id)
 Gets the current joint translation. More...
 
constexpr auto GetLength (const DistanceJointConf &object) noexcept
 Free function for getting the length value of the given configuration.
 
Length GetLength (const Joint &object)
 Gets the length property of the specified joint if its type has one. More...
 
template<typename T >
constexpr auto GetLength (const T &conf) noexcept -> decltype(std::declval< T >().length)
 Gets the length property of the given object.
 
Length GetLength (const World &world, JointID id)
 Gets the length associated with the identified joint if it has one. More...
 
constexpr auto GetLengthA (const PulleyJointConf &object) noexcept
 Free function for getting the length A value of the given configuration.
 
constexpr auto GetLengthB (const PulleyJointConf &object) noexcept
 Free function for getting the length B value of the given configuration.
 
LimitState GetLimitState (const Joint &object)
 
template<typename T >
constexpr auto GetLimitState (const T &conf) noexcept -> decltype(std::declval< T >().limitState)
 Gets the limit state property of the given object.
 
LimitState GetLimitState (const World &world, JointID id)
 Gets the joint's limit state if it has one. More...
 
LinearAcceleration2 GetLinearAcceleration (const Body &body) noexcept
 Gets this body's linear acceleration. More...
 
LinearAcceleration2 GetLinearAcceleration (const World &world, BodyID id)
 Gets this body's linear acceleration. More...
 
NonNegative< FrequencyGetLinearDamping (const Body &body) noexcept
 Gets the linear damping of the body. More...
 
Frequency GetLinearDamping (const World &world, BodyID id)
 Gets the linear damping of the body. More...
 
constexpr auto GetLinearError (const MotorJointConf &object) noexcept
 Free function for getting the linear error value of the given configuration.
 
Length GetLinearLowerLimit (const Joint &object)
 
constexpr auto GetLinearLowerLimit (const PrismaticJointConf &conf) noexcept
 Free function for getting the linear lower limit value of the given configuration.
 
Momentum GetLinearMotorImpulse (const Joint &object)
 
template<typename T >
constexpr auto GetLinearMotorImpulse (const T &conf) noexcept -> decltype(std::declval< T >().motorImpulse)
 Gets the linear motor impulse property of the given object.
 
Momentum GetLinearMotorImpulse (const World &world, JointID id)
 Gets the linear motor impulse of the identified joint if it supports that. More...
 
Length2 GetLinearOffset (const Joint &object)
 Gets the linear offset property of the specified joint if its type has one. More...
 
constexpr auto GetLinearOffset (const MotorJointConf &object) noexcept
 Free function for getting the linear offset value of the given configuration.
 
template<typename T >
constexpr auto GetLinearOffset (const T &conf) noexcept -> decltype(std::declval< T >().linearOffset)
 Gets the linear offset property of the given object.
 
Length2 GetLinearOffset (const World &world, JointID id)
 Gets the target linear offset, in frame A. More...
 
constexpr Momentum2 GetLinearReaction (const DistanceJointConf &object) noexcept
 Gets the current linear reaction for the given configuration.
 
constexpr Momentum2 GetLinearReaction (const FrictionJointConf &object) noexcept
 Gets the current linear reaction for the given configuration.
 
constexpr Momentum2 GetLinearReaction (const GearJointConf &object)
 Gets the current linear reaction for the given configuration.
 
Momentum2 GetLinearReaction (const Joint &object)
 
Momentum2 GetLinearReaction (const PrismaticJointConf &conf)
 Gets the current linear reaction of the given configuration.
 
constexpr Momentum2 GetLinearReaction (const PulleyJointConf &object) noexcept
 Gets the current linear reaction of the given configuration.
 
constexpr Momentum2 GetLinearReaction (const RevoluteJointConf &conf) noexcept
 Gets the current linear reaction of the given configuration.
 
constexpr Momentum2 GetLinearReaction (const RopeJointConf &object) noexcept
 Gets the current linear reaction of the given configuration.
 
template<typename T >
constexpr auto GetLinearReaction (const T &conf) noexcept -> decltype(std::declval< T >().linearImpulse)
 Gets the linear reaction property of the given object.
 
constexpr Momentum2 GetLinearReaction (const TargetJointConf &object)
 Gets the current linear reaction of the given configuration.
 
constexpr Momentum2 GetLinearReaction (const WeldJointConf &object) noexcept
 Gets the current linear reaction of the given configuration.
 
constexpr Momentum2 GetLinearReaction (const WheelJointConf &object)
 Gets the current linear reaction for the given configuration.
 
Momentum2 GetLinearReaction (const World &world, JointID id)
 Gets the linear reaction on body-B at the joint anchor. More...
 
Length GetLinearUpperLimit (const Joint &object)
 
constexpr auto GetLinearUpperLimit (const PrismaticJointConf &conf) noexcept
 Free function for getting the linear upper limit value of the given configuration.
 
LinearVelocity2 GetLinearVelocity (const Body &body) noexcept
 Gets the linear velocity of the center of mass. More...
 
LinearVelocity2 GetLinearVelocity (const World &world, BodyID id)
 Gets the linear velocity of the center of mass of the identified body. More...
 
LinearVelocity GetLinearVelocity (const World &world, const PrismaticJointConf &joint) noexcept
 Gets the current linear velocity of the given configuration. More...
 
LinearVelocity2 GetLinearVelocityFromLocalPoint (const Body &body, const Length2 &localPoint) noexcept
 Gets the linear velocity from a local point. More...
 
LinearVelocity2 GetLinearVelocityFromWorldPoint (const Body &body, const Length2 &worldPoint) noexcept
 Gets the linear velocity from a world point attached to this body. More...
 
Length2 GetLocalAnchorA (const GearJointConf &conf)
 Gets the local anchor A property of the given joint.
 
Length2 GetLocalAnchorA (const Joint &object)
 
constexpr auto GetLocalAnchorA (const MotorJointConf &) noexcept
 Gets the local anchor A.
 
template<typename T >
constexpr auto GetLocalAnchorA (const T &conf) noexcept -> decltype(std::declval< T >().localAnchorA)
 Gets the local anchor A property of the given object.
 
constexpr auto GetLocalAnchorA (const TargetJointConf &) noexcept
 Gets the local anchar A for the given configuration.
 
Length2 GetLocalAnchorA (const World &world, JointID id)
 
Length2 GetLocalAnchorB (const GearJointConf &conf)
 Gets the local anchor B property of the given joint.
 
Length2 GetLocalAnchorB (const Joint &object)
 
constexpr auto GetLocalAnchorB (const MotorJointConf &) noexcept
 Gets the local anchor B.
 
template<typename T >
constexpr auto GetLocalAnchorB (const T &conf) noexcept -> decltype(std::declval< T >().localAnchorB)
 Gets the local anchor B property of the given object.
 
Length2 GetLocalAnchorB (const World &world, JointID id)
 
Length2 GetLocalCenter (const Body &body) noexcept
 Gets the local position of the center of mass.
 
Length2 GetLocalCenter (const World &world, BodyID id)
 Gets the local position of the center of mass of the specified body. More...
 
Length2 GetLocalPoint (const Body &body, const Length2 &worldPoint) noexcept
 Gets a local point relative to the body's origin given a world point. More...
 
Length2 GetLocalPoint (const World &world, BodyID id, const Length2 &worldPoint)
 Gets a local point relative to the body's origin given a world point. More...
 
RotInertia GetLocalRotInertia (const Body &body) noexcept
 Gets the rotational inertia of the body about the local origin. More...
 
RotInertia GetLocalRotInertia (const World &world, BodyID id)
 Gets the rotational inertia of the body about the local origin. More...
 
UnitVec GetLocalVector (const Body &body, const UnitVec &uv) noexcept
 Gets a locally oriented unit vector given a world oriented unit vector. More...
 
UnitVec GetLocalVector (const World &world, BodyID body, const UnitVec &uv)
 Convenience function for getting the local vector of the identified body. More...
 
UnitVec GetLocalXAxisA (const Joint &object)
 Gets the given joint's local X axis A if its type supports that. More...
 
template<typename T >
constexpr auto GetLocalXAxisA (const T &conf) noexcept -> decltype(std::declval< T >().localXAxisA)
 Gets the local X axis A property of the given object.
 
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 Joint &object)
 Gets the given joint's local Y axis A if its type supports that. More...
 
template<typename T >
constexpr auto GetLocalYAxisA (const T &conf) noexcept -> decltype(std::declval< T >().localYAxisA)
 Gets the local Y axis A property of the given object.
 
UnitVec GetLocalYAxisA (const World &world, JointID id)
 Gets the local-Y-axis-A property of the identified joint if it has it. More...
 
Length2 GetLocation (const Body &body) noexcept
 Gets the body's origin location. More...
 
constexpr auto GetLocation (const BodyConf &conf) noexcept -> Length2
 Gets the location of the given configuration.
 
constexpr Length2 GetLocation (const Transformation &value) noexcept
 Gets the location information from the given transformation.
 
Length2 GetLocation (const World &world, BodyID id)
 Convenience function for getting just the location of the identified body. More...
 
Manifold GetManifold (bool flipped, const DistanceProxy &shape0, const Transformation &xf0, VertexCounter idx0, const DistanceProxy &shape1, const Transformation &xf1, VertexCounter2 indices1, const Manifold::Conf &conf)
 Gets a face-to-face based manifold. More...
 
Manifold GetManifold (bool flipped, Length totalRadius, const DistanceProxy &shape, const Transformation &sxf, const Length2 &point, const Transformation &xfm)
 Computes manifolds for face-to-point collision. More...
 
Manifold GetManifold (const Length2 &locationA, const Transformation &xfA, const Length2 &locationB, const Transformation &xfB, Length totalRadius) noexcept
 Gets a point-to-point based manifold.
 
Manifold GetManifold (const World &world, ContactID id)
 Gets the manifold for the identified contact. More...
 
Manifold::Conf GetManifoldConf (const StepConf &conf) noexcept
 Gets the manifold configuration for the given step configuration.
 
Mass GetMass (const Body &body) noexcept
 Gets the mass of the body. More...
 
Mass GetMass (const World &world, BodyID id)
 Gets the mass of the body. More...
 
MassData GetMassData (const ChainShapeConf &arg)
 Gets the mass data for a given chain shape configuration.
 
MassData GetMassData (const DiskShapeConf &arg)
 Gets the mass data of the given disk shape configuration.
 
MassData GetMassData (const EdgeShapeConf &arg)
 Gets the mass data for the given shape configuration.
 
MassData GetMassData (const MultiShapeConf &arg)
 Gets the mass data for the given shape configuration. More...
 
MassData GetMassData (const PolygonShapeConf &arg)
 Gets the mass data for the given shape configuration.
 
MassData GetMassData (const Shape &shape)
 Gets the mass properties of this shape using its dimensions and density. More...
 
MassData GetMassData (const World &world, BodyID id)
 Gets the mass data of the body. More...
 
MassData GetMassData (const World &world, ShapeID id)
 Gets the mass data for the identified shape in the given world. More...
 
MassData GetMassData (Length r, NonNegative< AreaDensity > density, const Length2 &location)
 Computes the mass data for a circular shape. More...
 
MassData GetMassData (Length r, NonNegative< AreaDensity > density, const Length2 &v0, const Length2 &v1)
 Computes the mass data for a linear shape. More...
 
MassData GetMassData (Length vertexRadius, NonNegative< AreaDensity > density, Span< const Length2 > vertices)
 Gets the mass data for the given collection of vertices with the given properties.
 
constexpr auto GetMaxForce (const FrictionJointConf &object) noexcept
 Free function for getting the max force value of the given configuration.
 
Force GetMaxForce (const Joint &object)
 Gets the given joint's max force if its type supports that. More...
 
constexpr auto GetMaxForce (const MotorJointConf &object) noexcept
 Free function for getting the maximum force value of the given configuration.
 
template<typename T >
constexpr auto GetMaxForce (const T &conf) noexcept -> decltype(std::declval< T >().maxForce)
 Gets the max force property of the given object.
 
constexpr auto GetMaxForce (const TargetJointConf &object) noexcept
 Free function for getting the maximum force value of the given configuration.
 
DynamicTree::Height GetMaxImbalance (const DynamicTree &tree) noexcept
 Gets the maximum imbalance. More...
 
constexpr auto GetMaxLength (const RopeJointConf &object) noexcept
 Free function for getting the maximum length value of the given configuration.
 
Force GetMaxMotorForce (const Joint &object)
 Gets the given joint's max motor force if its type supports that. More...
 
template<typename T >
constexpr auto GetMaxMotorForce (const T &conf) noexcept -> decltype(std::declval< T >().maxMotorForce)
 Gets the max motor force property of the given object.
 
Torque GetMaxMotorTorque (const Joint &object)
 Gets the given joint's max motor torque if its type supports that. More...
 
template<typename T >
constexpr auto GetMaxMotorTorque (const T &conf) noexcept -> decltype(std::declval< T >().maxMotorTorque)
 Gets the max motor torque property of the given object.
 
Torque GetMaxMotorTorque (const World &world, JointID id)
 Gets the max motor torque. More...
 
Momentum GetMaxNormalImpulse (const ContactImpulsesList &impulses) noexcept
 Gets the maximum normal impulse from the given contact impulses list.
 
SeparationInfo GetMaxSeparation (const DistanceProxy &proxy1, const DistanceProxy &proxy2, Length stop=MaxFloat *Meter)
 Gets the max separation information. More...
 
SeparationInfo GetMaxSeparation (const DistanceProxy &proxy1, const Transformation &xf1, const DistanceProxy &proxy2, const Transformation &xf2)
 Gets the max separation information. More...
 
SeparationInfo GetMaxSeparation (const DistanceProxy &proxy1, const Transformation &xf1, const DistanceProxy &proxy2, const Transformation &xf2, Length stop)
 Gets the max separation information. More...
 
SeparationInfo GetMaxSeparation4x4 (const DistanceProxy &proxy1, const Transformation &xf1, const DistanceProxy &proxy2, const Transformation &xf2)
 Gets the max separation information for the first four vertices of the two given shapes. More...
 
constexpr auto GetMaxTorque (const FrictionJointConf &object) noexcept
 Free function for getting the max torque value of the given configuration.
 
Torque GetMaxTorque (const Joint &object)
 Gets the given joint's max torque if its type supports that. More...
 
constexpr auto GetMaxTorque (const MotorJointConf &object) noexcept
 Free function for getting the maximum torque value of the given configuration.
 
template<typename T >
constexpr auto GetMaxTorque (const T &conf) noexcept -> decltype(std::declval< T >().maxTorque)
 Gets the max torque property of the given object.
 
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...
 
MotorJointConf GetMotorJointConf (const Joint &joint)
 Gets the definition data for the given joint. More...
 
MotorJointConf GetMotorJointConf (const World &world, BodyID bA, BodyID bB)
 Gets the confguration for the given parameters. More...
 
AngularVelocity GetMotorSpeed (const Joint &object)
 Gets the given joint's motor speed if its type supports that. More...
 
template<typename T >
constexpr auto GetMotorSpeed (const T &conf) noexcept -> decltype(std::declval< T >().motorSpeed)
 Gets the motor speed property of the given object.
 
AngularVelocity GetMotorSpeed (const World &world, JointID id)
 Gets the motor-speed property of the identied joint if it supports it. More...
 
Torque GetMotorTorque (const Joint &joint, Frequency inv_dt)
 Gets the current motor torque 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...
 
const char * GetName (Manifold::Type type) noexcept
 Gets a unique name for the given manifold type. More...
 
constexpr DynamicTree::Size GetNext (const DynamicTree::TreeNode &node) noexcept
 Gets the next index of the given node. More...
 
ChildCounter GetNextIndex (const ChainShapeConf &shape, ChildCounter index) noexcept
 Gets the next index after the given index for the given shape.
 
UnitVec GetNormal (const VelocityConstraint &vc) noexcept
 
Momentum GetNormalImpulseAtPoint (const VelocityConstraint &vc, VelocityConstraint::size_type index)
 Gets the normal impulse at the given point from the given velocity constraint.
 
Momentum2 GetNormalImpulses (const VelocityConstraint &vc)
 Gets the normal impulses of the given velocity constraint.
 
Position GetNormalized (const Position &val) noexcept
 Gets the "normalized" position. More...
 
Sweep GetNormalized (Sweep sweep) noexcept
 Gets a sweep with the given sweep's angles normalized. More...
 
Mass GetNormalMassAtPoint (const VelocityConstraint &vc, VelocityConstraint::size_type index)
 Gets the normal mass at the given point from the given velocity constraint.
 
constexpr Length GetPerimeter (const AABB &aabb) noexcept
 Gets the perimeter length of the 2-dimensional AABB. More...
 
constexpr Length2 GetPointDelta (const SimplexEdge &sv) noexcept
 Gets "w". More...
 
Length2 GetPointRelPosA (const VelocityConstraint &vc, VelocityConstraint::size_type index)
 Gets the point relative position A data.
 
Length2 GetPointRelPosB (const VelocityConstraint &vc, VelocityConstraint::size_type index)
 Gets the point relative position B data.
 
PointStates GetPointStates (const Manifold &manifold1, const Manifold &manifold2) noexcept
 Computes the before and after like point states given two manifolds. More...
 
Position GetPosition (const Body &body) noexcept
 Gets the body's position.
 
Position GetPosition (const Position &pos0, const Position &pos1, Real beta) noexcept
 
Position GetPosition (const World &world, BodyID id)
 Convenience function for getting the position of the identified body.
 
Position GetPosition0 (const Body &body) noexcept
 Gets the "position 0" Position information for the given body.
 
Position GetPosition1 (const Body &body) noexcept
 Gets the "position 1" Position information for the given body.
 
PrismaticJointConf GetPrismaticJointConf (const Joint &joint)
 Gets the definition data for the given joint. More...
 
PrismaticJointConf GetPrismaticJointConf (const World &world, BodyID bA, BodyID bB, const Length2 &anchor, const UnitVec &axis)
 Gets the configuration for the given parameters. More...
 
PositionSolverManifold GetPSM (const Manifold &manifold, Manifold::size_type index, const Transformation &xfA, const Transformation &xfB)
 Gets the normal-point-separation data in world coordinates for the given inputs. More...
 
PulleyJointConf GetPulleyJointConf (const Joint &joint)
 Gets the definition data for the given joint. More...
 
PulleyJointConf GetPulleyJointConf (const World &world, BodyID bA, BodyID bB, const Length2 &groundA, const Length2 &groundB, const Length2 &anchorA, const Length2 &anchorB)
 Gets the configuration for the given parameters. More...
 
constexpr auto GetRatio (const GearJointConf &object) noexcept
 Free function for getting the ratio value of the given configuration.
 
Real GetRatio (const Joint &object)
 Gets the given joint's ratio property if it has one. More...
 
template<typename T >
constexpr auto GetRatio (const T &conf) noexcept -> decltype(std::declval< T >().ratio)
 Gets the ratio property of the given object.
 
Real GetRatio (const World &world, JointID id)
 Gets the ratio property of the identified joint if it has it. More...
 
Angle GetReferenceAngle (const Joint &object)
 Gets the reference angle of the joint if it has one. More...
 
template<typename T >
constexpr auto GetReferenceAngle (const T &conf) noexcept -> decltype(std::declval< T >().referenceAngle)
 Gets the reference angle property of the given object.
 
Angle GetReferenceAngle (const World &world, JointID id)
 Gets the reference-angle property of the identified joint if it has it. More...
 
constexpr auto GetReflectionMatrix (const UnitVec &axis)
 Gets the reflection matrix for the given unit vector that defines the normal of the line through the origin that points should be reflected against. More...
 
VelocityConstraint::Conf GetRegVelocityConstraintConf (const StepConf &conf) noexcept
 Gets the regular phase velocity constraint configuration from the given step configuration.
 
std::optional< pmr::StatsResource::StatsGetResourceStats (const World &world) noexcept
 Gets the polymorphic memory resource allocator statistics of the specified world. More...
 
constexpr Finite< RealGetRestitution (const BaseShapeConf &arg) noexcept
 Gets the restitution of the given shape.
 
Real GetRestitution (const Shape &shape) noexcept
 Gets the coefficient of restitution value of the given shape. More...
 
Real GetRestitution (const World &world, ContactID id)
 Gets the restitution used with the identified contact. More...
 
Real GetRestitution (const World &world, ShapeID id)
 Gets the coefficient of restitution of the specified shape. More...
 
RevoluteJointConf GetRevoluteJointConf (const Joint &joint)
 Gets the definition data for the given joint. More...
 
RevoluteJointConf GetRevoluteJointConf (const World &world, BodyID bodyA, BodyID bodyB, const Length2 &anchor)
 Gets the configuration for the given parameters. More...
 
constexpr UnitVec GetRevPerpendicular (const UnitVec &vector) noexcept
 Gets a vector counter-clockwise (reverse-clockwise) perpendicular to the given vector. More...
 
RopeJointConf GetRopeJointConf (const Joint &joint)
 Gets the definition data for the given joint. More...
 
RotInertia GetRotInertia (const Body &body) noexcept
 Gets the rotational inertia of the body. More...
 
RotInertia GetRotInertia (const World &world, BodyID id)
 Gets the rotational inertia of the body. More...
 
Length2 GetScaledDelta (const Simplex &simplex, Simplex::size_type index)
 Gets the scaled delta for the given indexed element of the given simplex.
 
SeparationScenario GetSeparationScenario (IndexPair3 indices, const DistanceProxy &proxyA, const Transformation &xfA, const DistanceProxy &proxyB, const Transformation &xfB)
 Gets a separation finder for the given inputs. More...
 
Shape GetShape (const World &world, ShapeID id)
 Gets the shape associated with the identifier. More...
 
ShapeID GetShapeA (const World &world, ContactID id)
 Gets shape A of the identified contact. More...
 
ShapeID GetShapeB (const World &world, ContactID id)
 Gets shape B of the identified contact. More...
 
ShapeCounter GetShapeCount (const World &world, BodyID id)
 Gets the count of shapes associated with the identified body. More...
 
ShapeCounter GetShapeRange (const World &world) noexcept
 Gets the extent of the currently valid shape range. More...
 
const std::vector< ShapeID > & GetShapes (const AabbTreeWorld &world, BodyID id)
 Disassociates all of the associated shape from the validly identified body. More...
 
const std::vector< ShapeID > & GetShapes (const Body &body) noexcept
 Gets the identifiers of the shapes attached to the body.
 
std::vector< ShapeIDGetShapes (const World &world, BodyID id)
 Gets the identities of the shapes associated with the identified body. More...
 
ContactID GetSoonestContact (const Span< const KeyedContactID > &ids, const Span< const Contact > &contacts) noexcept
 Gets the identifier of the contact with the lowest time of impact. More...
 
bool GetSubStepping (const World &world) noexcept
 Gets whether or not sub-stepping is enabled. More...
 
template<class T >
VertexCounter GetSupportIndex (const DistanceProxy &proxy, T dir) noexcept
 Gets the supporting vertex index in given direction for given distance proxy. More...
 
const SweepGetSweep (const Body &body) noexcept
 Gets the body's sweep. More...
 
UnitVec GetTangent (const VelocityConstraint &vc) noexcept
 Gets the tangent from the given velocity constraint data.
 
Momentum GetTangentImpulseAtPoint (const VelocityConstraint &vc, VelocityConstraint::size_type index)
 Gets the tangent impulse at the given point from the given velocity constraint.
 
Momentum2 GetTangentImpulses (const VelocityConstraint &vc)
 Gets the tangent impulses of the given velocity constraint.
 
Mass GetTangentMassAtPoint (const VelocityConstraint &vc, VelocityConstraint::size_type index)
 Gets the tangent mass at the given point from the given velocity constraint.
 
LinearVelocity GetTangentSpeed (const World &world, ContactID id)
 Gets the tangent speed of the identified contact. More...
 
Length2 GetTarget (const Joint &object)
 Gets the given joint's target property if it has one. More...
 
constexpr auto GetTarget (const TargetJointConf &object) noexcept
 Free function for getting the target value of the given configuration.
 
Length2 GetTarget (const World &world, JointID id)
 Gets the target point. More...
 
TargetJointConf GetTargetJointConf (const Joint &joint)
 Gets the definition data for the given joint. More...
 
std::optional< UnitIntervalFF< Real > > GetToi (const World &world, ContactID id)
 Gets the time of impact (TOI) as a fraction or empty value. More...
 
TimestepIters GetToiCount (const World &world, ContactID id)
 Gets the Time Of Impact (TOI) count. More...
 
VelocityConstraint::Conf GetToiVelocityConstraintConf (const StepConf &conf) noexcept
 Gets the TOI phase velocity constraint configuration from the given step configuration.
 
ToiOutput GetToiViaSat (const DistanceProxy &proxyA, const Sweep &sweepA, const DistanceProxy &proxyB, const Sweep &sweepB, const ToiConf &conf=GetDefaultToiConf())
 Gets the time of impact for two disjoint convex sets using the Separating Axis Theorem. More...
 
Torque GetTorque (const Body &body) noexcept
 Gets the net torque that the given body is currently experiencing.
 
ContactCounter GetTouchingCount (const World &world)
 Gets the touching count for the given world. More...
 
Transformation GetTransform0 (const Sweep &sweep) noexcept
 Gets the transform at "time" zero. More...
 
Transformation GetTransform1 (const Sweep &sweep) noexcept
 Gets the transform at "time" one. More...
 
const TransformationGetTransformation (const Body &body) noexcept
 Gets the body's transformation. More...
 
constexpr Transformation GetTransformation (const Length2 &ctr, const UnitVec &rot, const Length2 &localCtr) noexcept
 Gets the transformation for the given values.
 
Transformation GetTransformation (const Position &pos, const Length2 &local_ctr) noexcept
 Gets the transformation for the given values.
 
Transformation GetTransformation (const Sweep &sweep, const UnitIntervalFF< Real > beta) noexcept
 Gets the interpolated transform at a specific time. More...
 
Transformation GetTransformation (const World &world, BodyID id)
 Gets the body's transformation. More...
 
const DynamicTreeGetTree (const World &world)
 Gets access to the broad-phase dynamic tree information. More...
 
BodyType GetType (const Body &body) noexcept
 Gets the type of this body. More...
 
TypeID GetType (const Joint &object) noexcept
 Gets the identifier of the type of data this can be casted to.
 
TypeID GetType (const Shape &shape) noexcept
 Gets the type info of the use of the given shape. More...
 
TypeID GetType (const World &world) noexcept
 Gets the identifier of the type of data the given world can be casted to. More...
 
BodyType GetType (const World &world, BodyID id)
 Gets the type of the identified body. More...
 
TypeID GetType (const World &world, JointID id)
 Gets the type of the joint. More...
 
TypeID GetType (const World &world, ShapeID id)
 Gets the type of the shape. More...
 
TypeID GetTypeAC (const GearJointConf &object) noexcept
 Free function for getting joint 1 type value of the given configuration.
 
TypeID GetTypeBD (const GearJointConf &object) noexcept
 Free function for getting joint 2 type value of the given configuration.
 
Time GetUnderActiveTime (const Body &body) noexcept
 Gets the given body's under-active time. More...
 
template<class T >
UnitVec GetUnitVector (const Vector2< T > &value, const UnitVec &fallback=UnitVec::GetDefaultFallback()) noexcept
 
ShapeCounter GetUsedShapesCount (const World &world) noexcept
 Gets the count of uniquely identified shapes that are in use - i.e. that are attached to bodies. More...
 
constexpr Vec2 GetVec2 (const UnitVec &value)
 Gets a Vec2 representation of the given value.
 
Velocity GetVelocity (const Body &body) noexcept
 Gets the velocity. More...
 
Velocity GetVelocity (const Body &body, Time h) noexcept
 Gets the velocity of the body after the given time accounting for the body's acceleration and capped by the given configuration. More...
 
Velocity GetVelocity (const World &world, BodyID id)
 Gets the velocity of the identified body. More...
 
LinearVelocity GetVelocityBiasAtPoint (const VelocityConstraint &vc, VelocityConstraint::size_type index)
 Gets the velocity bias at the given point from the given velocity constraint.
 
VertexCounter GetVertexCount (const Shape &shape, ChildCounter index)
 Gets the vertex count for the specified child of the given shape.
 
NonNegative< LengthGetVertexRadius (const ChainShapeConf &arg) noexcept
 Gets the vertex radius of the given shape configuration.
 
NonNegative< LengthGetVertexRadius (const ChainShapeConf &arg, ChildCounter) noexcept
 Gets the vertex radius of the given shape configuration.
 
constexpr NonNegative< LengthGetVertexRadius (const DiskShapeConf &arg) noexcept
 Gets the vertex radius of the given shape configuration.
 
constexpr NonNegative< LengthGetVertexRadius (const DiskShapeConf &arg, ChildCounter) noexcept
 Gets the vertex radius of the given shape configuration.
 
auto GetVertexRadius (const DistanceProxy &arg) noexcept
 Gets the vertex radius property of a given distance proxy.
 
NonNegative< LengthGetVertexRadius (const EdgeShapeConf &arg) noexcept
 Gets the vertex radius of the given shape configuration.
 
NonNegative< LengthGetVertexRadius (const EdgeShapeConf &arg, ChildCounter) noexcept
 Gets the vertex radius of the given shape configuration.
 
NonNegative< LengthGetVertexRadius (const MultiShapeConf &arg, ChildCounter index)
 Gets the vertex radius of the given shape configuration.
 
NonNegative< LengthGetVertexRadius (const PolygonShapeConf &arg) noexcept
 Gets the vertex radius of the given shape configuration.
 
NonNegative< LengthGetVertexRadius (const PolygonShapeConf &arg, ChildCounter) noexcept
 Gets the vertex radius of the given shape configuration.
 
NonNegative< LengthGetVertexRadius (const Shape &shape, ChildCounter idx)
 Gets the vertex radius of the indexed child of the given shape. More...
 
Interval< Positive< Length > > GetVertexRadiusInterval (const World &world) noexcept
 Gets the vertex radius interval allowable for the given world. More...
 
WeldJointConf GetWeldJointConf (const Joint &joint)
 Gets the definition data for the given joint. More...
 
WeldJointConf GetWeldJointConf (const World &world, BodyID bodyA, BodyID bodyB, const Length2 &anchor=Length2{})
 Gets the configuration for the given parameters. More...
 
WheelJointConf GetWheelJointConf (const Joint &joint)
 Gets the definition data for the given joint. More...
 
WheelJointConf GetWheelJointConf (const World &world, BodyID bodyA, BodyID bodyB, const Length2 &anchor, const UnitVec &axis=UnitVec::GetRight())
 Gets the definition data for the given parameters. More...
 
PairLength2 GetWitnessPoints (const Simplex &simplex) noexcept
 Gets the witness points of the given simplex.
 
Length2 GetWorldCenter (const Body &body) noexcept
 Get the world position of the center of mass.
 
Length2 GetWorldCenter (const World &world, BodyID id)
 Get the world position of the center of mass of the specified body. More...
 
BodyCounter GetWorldIndex (const World &, BodyID id) noexcept
 Gets the world index for the given body. More...
 
JointCounter GetWorldIndex (const World &, JointID id) noexcept
 Gets the world index of the given joint. More...
 
WorldManifold GetWorldManifold (const Manifold &manifold, const Transformation &xfA, Length radiusA, const Transformation &xfB, Length radiusB)
 Gets the world manifold for the given data. More...
 
WorldManifold GetWorldManifold (const World &world, const Contact &contact, const Manifold &manifold)
 
WorldManifold GetWorldManifold (const World &world, ContactID id)
 Gets the world manifold for the identified contact. More...
 
Length2 GetWorldPoint (const Body &body, const Length2 &localPoint) noexcept
 Gets the world coordinates of a point given in coordinates relative to the body's origin. 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...
 
Length2 GetWorldVector (const Body &body, const Length2 &localVector) noexcept
 Gets the world coordinates of a vector given the local coordinates. More...
 
UnitVec GetWorldVector (const Body &body, const UnitVec &localVector) noexcept
 Gets the world vector for the given local vector from the given body's transformation.
 
UnitVec GetWorldVector (const World &world, BodyID id, const UnitVec &localVector)
 Convenience function for getting a world vector of the identified body. More...
 
constexpr auto GetX (const UnitVec &value)
 Gets the "X" element of the given value - i.e. the first element.
 
constexpr UnitVec GetXAxis (const UnitVec &rot) noexcept
 Gets the "X-axis".
 
constexpr auto GetY (const UnitVec &value) -> decltype(get< 1 >(value))
 Gets the "Y" element of the given value - i.e. the second element.
 
constexpr UnitVec GetYAxis (const UnitVec &rot) noexcept
 Gets the "Y-axis". More...
 
bool HasValidToi (const World &world, ContactID id)
 Whether or not the contact has a valid TOI. More...
 
void InitVelocity (DistanceJointConf &object, const Span< BodyConstraint > &bodies, const StepConf &step, const ConstraintSolverConf &conf)
 Initializes velocity constraint data based on the given solver data. More...
 
void InitVelocity (FrictionJointConf &object, const Span< BodyConstraint > &bodies, const StepConf &step, const ConstraintSolverConf &conf)
 Initializes velocity constraint data based on the given solver data. More...
 
void InitVelocity (GearJointConf &object, const Span< BodyConstraint > &bodies, const StepConf &step, const ConstraintSolverConf &conf)
 Initializes velocity constraint data based on the given solver data. More...
 
void InitVelocity (Joint &object, const Span< BodyConstraint > &bodies, const StepConf &step, const ConstraintSolverConf &conf)
 Initializes velocity constraint data based on the given solver data. More...
 
void InitVelocity (MotorJointConf &object, const Span< BodyConstraint > &bodies, const StepConf &step, const ConstraintSolverConf &conf)
 Initializes velocity constraint data based on the given solver data. More...
 
void InitVelocity (PrismaticJointConf &object, const Span< BodyConstraint > &bodies, const StepConf &step, const ConstraintSolverConf &conf)
 Initializes velocity constraint data based on the given solver data. More...
 
void InitVelocity (PulleyJointConf &object, const Span< BodyConstraint > &bodies, const StepConf &step, const ConstraintSolverConf &conf)
 Initializes velocity constraint data based on the given solver data. More...
 
void InitVelocity (RevoluteJointConf &object, const Span< BodyConstraint > &bodies, const StepConf &step, const ConstraintSolverConf &conf)
 Initializes velocity constraint data based on the given solver data. More...
 
void InitVelocity (RopeJointConf &object, const Span< BodyConstraint > &bodies, const StepConf &step, const ConstraintSolverConf &conf)
 Initializes velocity constraint data based on the given solver data. More...
 
void InitVelocity (TargetJointConf &object, const Span< BodyConstraint > &bodies, const StepConf &step, const ConstraintSolverConf &conf)
 Initializes velocity constraint data based on the given solver data. More...
 
void InitVelocity (WeldJointConf &object, const Span< BodyConstraint > &bodies, const StepConf &step, const ConstraintSolverConf &conf)
 Initializes velocity constraint data based on the given solver data. More...
 
void InitVelocity (WheelJointConf &object, const Span< BodyConstraint > &bodies, const StepConf &step, const ConstraintSolverConf &conf)
 Initializes velocity constraint data based on the given solver data. More...
 
constexpr UnitVec InverseRotate (const UnitVec &vector, const UnitVec &angle) noexcept
 Inverse rotates a vector.
 
template<class T >
constexpr auto InverseRotate (const Vector2< T > &vector, const UnitVec &angle) noexcept
 Inverse rotates a vector. More...
 
constexpr Length2 InverseTransform (const Length2 &v, const Transformation &xfm) noexcept
 Inverse transforms the given 2-D vector with the given transformation. More...
 
bool IsAccelerable (const Body &body) noexcept
 Is "accelerable". More...
 
bool IsAccelerable (const World &world, BodyID id)
 Is identified body "accelerable"? More...
 
bool IsAwake (const Body &body) noexcept
 Gets the awake/asleep state of this body. More...
 
bool IsAwake (const World &world, BodyID id)
 Gets the awake/asleep state of this body. More...
 
bool IsAwake (const World &world, ContactID id)
 Gets the awake status of the specified contact. More...
 
constexpr bool IsBranch (const DynamicTree::TreeNode &node) noexcept
 Is branch. More...
 
constexpr auto IsDestroyed (const Body &body) noexcept -> bool
 Whether or not the given body was destroyed. More...
 
auto IsDestroyed (const Joint &object) noexcept -> bool
 Gets whether the given entity is in the is-destroyed state.
 
auto IsDestroyed (const Shape &value) noexcept -> bool
 Gets whether the given entity is in the is-destroyed state.
 
auto IsDestroyed (const World &world, BodyID id) -> bool
 Gets whether the given identifier is to a body that's been destroyed. More...
 
auto IsDestroyed (const World &world, ContactID id) -> bool
 Gets whether the given identifier is to a contact that's been destroyed. More...
 
auto IsDestroyed (const World &world, JointID id) -> bool
 Gets whether the given identifier is to a joint that's been destroyed. More...
 
auto IsDestroyed (const World &world, ShapeID id) -> bool
 Gets whether the given identifier is to a shape that's been destroyed. More...
 
bool IsEnabled (const Body &body) noexcept
 Gets the enabled/disabled state of the body. More...
 
bool IsEnabled (const World &world, BodyID id)
 Gets the enabled/disabled state of the body. More...
 
bool IsEnabled (const World &world, ContactID id)
 Gets the enabled status of the identified contact. More...
 
bool IsEnabled (const World &world, JointID id)
 Gets the enabled/disabled state of the joint. More...
 
bool IsFixedRotation (const Body &body) noexcept
 Does this body have fixed rotation? More...
 
bool IsFixedRotation (const World &world, BodyID id)
 Gets whether the body has fixed rotation. More...
 
bool IsImpenetrable (const Body &body) noexcept
 Is this body treated like a bullet for continuous collision detection? More...
 
bool IsImpenetrable (const World &world, BodyID id)
 Is the body treated like a bullet for continuous collision detection? More...
 
constexpr bool IsLeaf (const DynamicTree::TreeNode &node) noexcept
 Is leaf. More...
 
bool IsLimitEnabled (const Joint &object)
 Gets the specified joint's limit property if it supports one. More...
 
template<typename T >
constexpr auto IsLimitEnabled (const T &conf) noexcept -> decltype(std::declval< T >().enableLimit)
 Gets whether or not the limit property of the given object is enabled.
 
bool IsLimitEnabled (const World &world, JointID id)
 Gets whether the identified joint's limit is enabled. More...
 
bool IsLocked (const World &world) noexcept
 Is the specified world locked. More...
 
bool IsLooped (const ChainShapeConf &shape) noexcept
 Determines whether the given shape is looped.
 
bool IsMassDataDirty (const Body &body) noexcept
 Gets whether the mass data for this body is "dirty".
 
bool IsMassDataDirty (const World &world, BodyID id)
 Gets whether the body's mass-data is dirty. More...
 
bool IsMotorEnabled (const Joint &object)
 Gets the specified joint's motor property value if it supports one. More...
 
template<typename T >
constexpr auto IsMotorEnabled (const T &conf) noexcept -> decltype(std::declval< T >().enableMotor)
 Gets the motor enabled property of the given object.
 
bool IsMotorEnabled (const World &world, JointID id)
 
constexpr bool IsSensor (const BaseShapeConf &arg) noexcept
 Gets the is-sensor state of the given shape configuration.
 
bool IsSensor (const Shape &shape) noexcept
 Gets whether or not the given shape is a sensor. More...
 
bool IsSensor (const World &world, ShapeID id)
 Is the specified shape a sensor (non-solid)? More...
 
bool IsSleepingAllowed (const Body &body) noexcept
 Gets whether or not this body allowed to sleep. More...
 
bool IsSleepingAllowed (const World &world, BodyID id)
 Gets whether the identified body is allowed to sleep. More...
 
bool IsSpeedable (const Body &body) noexcept
 Is "speedable". More...
 
bool IsSpeedable (const World &world, BodyID id)
 Is identified body "speedable". More...
 
bool IsStepComplete (const World &world) noexcept
 Whether or not "step" is complete. More...
 
bool IsTouching (const World &world, ContactID id)
 Is this contact touching? More...
 
bool IsUnderActive (const Velocity &velocity, const LinearVelocity &linSleepTol, const AngularVelocity &angSleepTol) noexcept
 Gets whether the given velocity is "under active" based on the given tolerances.
 
constexpr bool IsUnused (const DynamicTree::TreeNode &node) noexcept
 Is unused. More...
 
auto MakeTouchingMap (const World &world) -> std::map< std::pair< Contactable, Contactable >, ContactID >
 Makes a map of contacts in the given world that are in the touching state.
 
constexpr Transformation Mul (const Transformation &A, const Transformation &B) noexcept
 Multiplies a given transformation by another given transformation. More...
 
constexpr Transformation MulT (const Transformation &A, const Transformation &B) noexcept
 Inverse multiplies a given transformation by another given transformation. 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...
 
constexpr bool operator!= (const Acceleration &lhs, const Acceleration &rhs)
 Inequality operator.
 
bool operator!= (const Body &lhs, const Body &rhs)
 Not-equals operator. More...
 
constexpr bool operator!= (const BodyConf &lhs, const BodyConf &rhs) noexcept
 Operator not-equals.
 
bool operator!= (const DiskShapeConf &lhs, const DiskShapeConf &rhs) noexcept
 Inequality operator.
 
constexpr bool operator!= (const DistanceJointConf &lhs, const DistanceJointConf &rhs) noexcept
 Inequality operator.
 
bool operator!= (const DistanceProxy &lhs, const DistanceProxy &rhs) noexcept
 Determines with the two given distance proxies are not equal.
 
bool operator!= (const EdgeShapeConf &lhs, const EdgeShapeConf &rhs) noexcept
 Inequality operator.
 
constexpr bool operator!= (const FrictionJointConf &lhs, const FrictionJointConf &rhs) noexcept
 Inequality operator.
 
constexpr bool operator!= (const GearJointConf &lhs, const GearJointConf &rhs) noexcept
 Inequality operator.
 
constexpr bool operator!= (const GearJointConf::PrismaticData &lhs, const GearJointConf::PrismaticData &rhs) noexcept
 Not equals operator.
 
constexpr bool operator!= (const GearJointConf::RevoluteData &lhs, const GearJointConf::RevoluteData &rhs) noexcept
 Not equals operator.
 
bool operator!= (const Joint &lhs, const Joint &rhs) noexcept
 Inequality operator for joint comparisons.
 
bool operator!= (const Manifold &lhs, const Manifold &rhs) noexcept
 Manifold inequality operator. More...
 
bool operator!= (const Manifold::Point &lhs, const Manifold::Point &rhs) noexcept
 Determines whether the two given manifold points are not equal.
 
constexpr bool operator!= (const MotorJointConf &lhs, const MotorJointConf &rhs) noexcept
 Inequality operator.
 
bool operator!= (const MultiShapeConf &lhs, const MultiShapeConf &rhs) noexcept
 Inequality operator.
 
constexpr bool operator!= (const Position &lhs, const Position &rhs)
 Inequality operator.
 
constexpr bool operator!= (const PrismaticJointConf &lhs, const PrismaticJointConf &rhs) noexcept
 Inequality operator.
 
constexpr bool operator!= (const PulleyJointConf &lhs, const PulleyJointConf &rhs) noexcept
 Inequality operator.
 
constexpr bool operator!= (const RevoluteJointConf &lhs, const RevoluteJointConf &rhs) noexcept
 Inequality operator.
 
constexpr bool operator!= (const RopeJointConf &lhs, const RopeJointConf &rhs) noexcept
 Inequality operator.
 
bool operator!= (const Shape &lhs, const Shape &rhs) noexcept
 Inequality operator for shape to shape comparisons.
 
constexpr bool operator!= (const SimplexEdge &lhs, const SimplexEdge &rhs) noexcept
 Inequality operator for SimplexEdge.
 
constexpr bool operator!= (const Sweep &lhs, const Sweep &rhs)
 Not-equals operator.
 
constexpr bool operator!= (const TargetJointConf &lhs, const TargetJointConf &rhs) noexcept
 Inequality operator.
 
constexpr bool operator!= (const Transformation &lhs, const Transformation &rhs) noexcept
 Inequality operator.
 
constexpr bool operator!= (const UnitVec &a, const UnitVec &b) noexcept
 Inequality operator.
 
constexpr bool operator!= (const Velocity &lhs, const Velocity &rhs)
 Inequality operator.
 
constexpr bool operator!= (const WeldJointConf &lhs, const WeldJointConf &rhs) noexcept
 Inequality operator.
 
constexpr bool operator!= (const WheelJointConf &lhs, const WheelJointConf &rhs) noexcept
 Inequality operator.
 
bool operator!= (const World &lhs, const World &rhs) noexcept
 Inequality operator for world comparisons. More...
 
constexpr Acceleration operator* (const Acceleration &lhs, const Real rhs)
 Multiplication operator.
 
template<class T , typename U , bool NoExcept>
constexpr Vector2< T > operator* (const playrho::detail::Checked< T, U, NoExcept > &s, const UnitVec &u) noexcept
 Multiplication operator.
 
constexpr Position operator* (const Position &pos, const Real scalar)
 Multiplication operator.
 
constexpr Acceleration operator* (const Real lhs, const Acceleration &rhs)
 Multiplication operator.
 
constexpr Velocity operator* (const Real lhs, const Velocity &rhs)
 Multiplication operator.
 
constexpr Position operator* (const Real scalar, const Position &pos)
 Multiplication operator.
 
template<class T >
constexpr Vector2< T > operator* (const T &s, const UnitVec &u) noexcept
 Multiplication operator.
 
template<class T , class U , bool NoExcept>
constexpr Vector2< T > operator* (const UnitVec &u, const playrho::detail::Checked< T, U, NoExcept > &s) noexcept
 Multiplication operator.
 
template<class T >
constexpr Vector2< T > operator* (const UnitVec &u, const T &s) noexcept
 Multiplication operator.
 
constexpr Velocity operator* (const Velocity &lhs, const Real rhs)
 Multiplication operator.
 
constexpr Accelerationoperator*= (Acceleration &lhs, const Real rhs)
 Multiplication assignment operator.
 
constexpr Velocityoperator*= (Velocity &lhs, const Real rhs)
 Multiplication assignment operator.
 
constexpr Acceleration operator+ (const Acceleration &lhs, const Acceleration &rhs)
 Addition operator.
 
constexpr Acceleration operator+ (const Acceleration &value)
 Positive operator.
 
constexpr Position operator+ (const Position &lhs, const Position &rhs)
 Addition operator.
 
constexpr Position operator+ (const Position &value)
 Positive operator.
 
PositionSolution operator+ (const PositionSolution &lhs, const PositionSolution &rhs)
 Addition operator.
 
constexpr Velocity operator+ (const Velocity &lhs, const Velocity &rhs)
 Addition operator.
 
constexpr Velocity operator+ (const Velocity &value)
 Positive operator.
 
constexpr Accelerationoperator+= (Acceleration &lhs, const Acceleration &rhs)
 Addition assignment operator.
 
constexpr Positionoperator+= (Position &lhs, const Position &rhs)
 Addition assignment operator.
 
constexpr Velocityoperator+= (Velocity &lhs, const Velocity &rhs)
 Addition assignment operator.
 
constexpr Acceleration operator- (const Acceleration &lhs, const Acceleration &rhs)
 Subtraction operator.
 
constexpr Acceleration operator- (const Acceleration &value)
 Negation operator.
 
constexpr Position operator- (const Position &lhs, const Position &rhs)
 Subtraction operator.
 
constexpr Position operator- (const Position &value)
 Negation operator.
 
PositionSolution operator- (const PositionSolution &lhs, const PositionSolution &rhs)
 Subtraction operator.
 
constexpr Velocity operator- (const Velocity &lhs, const Velocity &rhs)
 Subtraction operator.
 
constexpr Velocity operator- (const Velocity &value)
 Negation operator.
 
constexpr Accelerationoperator-= (Acceleration &lhs, const Acceleration &rhs)
 Subtraction assignment operator.
 
constexpr Positionoperator-= (Position &lhs, const Position &rhs)
 Subtraction assignment operator.
 
constexpr Velocityoperator-= (Velocity &lhs, const Velocity &rhs)
 Subtraction assignment operator.
 
constexpr Acceleration operator/ (const Acceleration &lhs, const Real rhs)
 Division operator.
 
constexpr Vec2 operator/ (const UnitVec &u, const UnitVec::value_type s) noexcept
 Division operator.
 
constexpr Velocity operator/ (const Velocity &lhs, const Real rhs)
 Division operator.
 
constexpr Accelerationoperator/= (Acceleration &lhs, const Real rhs)
 Division assignment operator.
 
constexpr Velocityoperator/= (Velocity &lhs, const Real rhs)
 Division assignment operator.
 
inline ::std::ostream & operator<< (::std::ostream &os, const UnitVec &value)
 Output stream operator.
 
constexpr bool operator== (const Acceleration &lhs, const Acceleration &rhs)
 Equality operator.
 
bool operator== (const Body &lhs, const Body &rhs)
 Equals operator. More...
 
constexpr bool operator== (const BodyConf &lhs, const BodyConf &rhs) noexcept
 Operator equals.
 
bool operator== (const DiskShapeConf &lhs, const DiskShapeConf &rhs) noexcept
 Equality operator.
 
constexpr bool operator== (const DistanceJointConf &lhs, const DistanceJointConf &rhs) noexcept
 Equality operator.
 
bool operator== (const DistanceProxy &lhs, const DistanceProxy &rhs) noexcept
 Determines with the two given distance proxies are equal.
 
bool operator== (const EdgeShapeConf &lhs, const EdgeShapeConf &rhs) noexcept
 Equality operator.
 
constexpr bool operator== (const FrictionJointConf &lhs, const FrictionJointConf &rhs) noexcept
 Equality operator.
 
constexpr bool operator== (const GearJointConf &lhs, const GearJointConf &rhs) noexcept
 Equality operator.
 
constexpr bool operator== (const GearJointConf::PrismaticData &lhs, const GearJointConf::PrismaticData &rhs) noexcept
 Equals operator.
 
constexpr bool operator== (const GearJointConf::RevoluteData &lhs, const GearJointConf::RevoluteData &rhs) noexcept
 Equals operator.
 
bool operator== (const Joint &lhs, const Joint &rhs) noexcept
 Equality operator for joint comparisons.
 
bool operator== (const Manifold &lhs, const Manifold &rhs) noexcept
 Manifold equality operator. More...
 
bool operator== (const Manifold::Point &lhs, const Manifold::Point &rhs) noexcept
 Determines whether the two given manifold points are equal.
 
constexpr bool operator== (const MotorJointConf &lhs, const MotorJointConf &rhs) noexcept
 Equality operator.
 
bool operator== (const MultiShapeConf &lhs, const MultiShapeConf &rhs) noexcept
 Equality operator.
 
constexpr bool operator== (const Position &lhs, const Position &rhs)
 Equality operator.
 
constexpr bool operator== (const PrismaticJointConf &lhs, const PrismaticJointConf &rhs) noexcept
 Equality operator.
 
constexpr bool operator== (const PulleyJointConf &lhs, const PulleyJointConf &rhs) noexcept
 Equality operator.
 
constexpr bool operator== (const RevoluteJointConf &lhs, const RevoluteJointConf &rhs) noexcept
 Equality operator.
 
constexpr bool operator== (const RopeJointConf &lhs, const RopeJointConf &rhs) noexcept
 Equality operator.
 
bool operator== (const Shape &lhs, const Shape &rhs) noexcept
 Equality operator for shape to shape comparisons.
 
constexpr bool operator== (const SimplexEdge &lhs, const SimplexEdge &rhs) noexcept
 Equality operator for SimplexEdge.
 
constexpr bool operator== (const Sweep &lhs, const Sweep &rhs)
 Equals operator.
 
constexpr bool operator== (const TargetJointConf &lhs, const TargetJointConf &rhs) noexcept
 Equality operator.
 
constexpr bool operator== (const Transformation &lhs, const Transformation &rhs) noexcept
 Equality operator.
 
constexpr bool operator== (const UnitVec &a, const UnitVec &b) noexcept
 Equality operator.
 
constexpr bool operator== (const Velocity &lhs, const Velocity &rhs)
 Equality operator.
 
constexpr bool operator== (const WeldJointConf &lhs, const WeldJointConf &rhs) noexcept
 Equality operator.
 
constexpr bool operator== (const WheelJointConf &lhs, const WheelJointConf &rhs) noexcept
 Equality operator.
 
bool operator== (const World &lhs, const World &rhs) noexcept
 Equality operator for world comparisons. More...
 
void Query (const DynamicTree &tree, const AABB &aabb, const DynamicTreeSizeCB &callback)
 Query the given dynamic tree and find nodes overlapping the given AABB. More...
 
void Query (const DynamicTree &tree, const AABB &aabb, QueryShapeCallback callback)
 Queries the world for all fixtures that potentially overlap the provided AABB. More...
 
RayCastOutput RayCast (const ::playrho::detail::AABB< 2 > &aabb, const RayCastInput &input) noexcept
 Cast a ray against the given AABB. More...
 
RayCastOutput RayCast (const DistanceProxy &proxy, const RayCastInput &input, const Transformation &transform) noexcept
 Cast a ray against the distance proxy. More...
 
bool RayCast (const DynamicTree &tree, RayCastInput input, const DynamicTreeRayCastCB &callback)
 Cast rays against the leafs in the given tree. More...
 
RayCastOutput RayCast (const Shape &shape, ChildCounter childIndex, const RayCastInput &input, const Transformation &transform) noexcept
 Cast a ray against the child of the given shape. More...
 
bool RayCast (const World &world, const RayCastInput &input, const ShapeRayCastCB &callback)
 Ray-cast the world for all fixtures in the path of the ray. More...
 
RayCastOutput RayCast (Length radius, const Length2 &location, const RayCastInput &input) noexcept
 Cast a ray against a circle of a given radius at the given location. More...
 
constexpr DynamicTreeBranchData ReplaceChild (DynamicTreeBranchData bd, DynamicTree::Size oldChild, DynamicTree::Size newChild)
 Replaces the old child with the new child. More...
 
void ResetFriction (World &world, ContactID id)
 
void ResetMassData (World &world, BodyID id)
 Resets the mass data properties. More...
 
void ResetRestitution (World &world, ContactID id)
 
void Rotate (ChainShapeConf &arg, const UnitVec &value)
 Rotates the given shape's vertices by the given amount.
 
constexpr UnitVec Rotate (const UnitVec &vector, const UnitVec &angle) noexcept
 Rotates a unit vector by the angle expressed by the second unit vector. More...
 
template<class T >
constexpr auto Rotate (const Vector2< T > &vector, const UnitVec &angle) noexcept
 Rotates a vector by a given angle. More...
 
void Rotate (DiskShapeConf &arg, const UnitVec &value) noexcept
 Rotates the given shape configuration's vertices by the given amount.
 
void Rotate (EdgeShapeConf &arg, const UnitVec &value) noexcept
 Rotates the given shape's vertices by the given amount.
 
void Rotate (MultiShapeConf &arg, const UnitVec &value)
 Rotates the given shape configuration's vertices by the given amount.
 
void Rotate (PolygonShapeConf &arg, const UnitVec &value)
 Rotates the given shape configuration's vertices by the given amount.
 
void Rotate (Shape &shape, const UnitVec &value)
 Rotates all of the given shape's vertices by the given amount. More...
 
void Rotate (World &world, ShapeID id, const UnitVec &value)
 Rotates all of the given shape's vertices by the given amount. More...
 
void RotateAboutLocalPoint (World &world, BodyID id, Angle amount, const Length2 &localPoint)
 Rotates a body a given amount around a point in body local coordinates. More...
 
void RotateAboutWorldPoint (World &world, BodyID id, Angle amount, const Length2 &worldPoint)
 Rotates a body a given amount around a point in world coordinates. More...
 
auto SameTouching (const World &lhs, const World &rhs) -> bool
 Determines whether the given worlds have the same touching contacts & manifolds.
 
void Scale (ChainShapeConf &arg, const Vec2 &value)
 Scales the given shape's vertices by the given amount.
 
void Scale (DiskShapeConf &arg, const Vec2 &value) noexcept
 Scales the given shape configuration's vertices by the given amount.
 
void Scale (EdgeShapeConf &arg, const Vec2 &value) noexcept
 Scales the given shape's vertices by the given amount.
 
void Scale (MultiShapeConf &arg, const Vec2 &value)
 Scales the given shape configuration's vertices by the given amount.
 
void Scale (PolygonShapeConf &arg, const Vec2 &value)
 Scales the given shape configuration's vertices by the given amount.
 
void Scale (Shape &shape, const Vec2 &value)
 Scales all of the given shape's vertices by the given amount. More...
 
void Scale (World &world, ShapeID id, const Vec2 &value)
 Scales all of the given shape's vertices by the given amount. More...
 
void Set (JointConf &def, const Joint &joint) noexcept
 Sets the joint definition data for the given joint.
 
void SetAcceleration (Body &body, AngularAcceleration value) noexcept
 Sets the given angular acceleration of the given body. More...
 
void SetAcceleration (Body &body, const Acceleration &value) noexcept
 Sets the accelerations on the given body. More...
 
void SetAcceleration (Body &body, const LinearAcceleration2 &linear, AngularAcceleration angular) noexcept
 Sets the linear and rotational accelerations on this body. More...
 
void SetAcceleration (Body &body, const LinearAcceleration2 &value) noexcept
 Sets the given linear acceleration of the given body. More...
 
void SetAcceleration (World &world, BodyID id, AngularAcceleration value)
 Sets the rotational accelerations on the body. More...
 
void SetAcceleration (World &world, BodyID id, const Acceleration &value)
 Sets the accelerations on the given body. More...
 
void SetAcceleration (World &world, BodyID id, const LinearAcceleration2 &linear, AngularAcceleration angular)
 Sets the linear and rotational accelerations on the body. More...
 
void SetAcceleration (World &world, BodyID id, const LinearAcceleration2 &value)
 Sets the linear accelerations on the body. More...
 
void SetAccelerations (World &world, const Acceleration &acceleration)
 Sets the accelerations of all the world's bodies to the given value. More...
 
void SetAccelerations (World &world, const LinearAcceleration2 &acceleration)
 Sets the accelerations of all the world's bodies to the given value. More...
 
template<class F >
void SetAccelerations (World &world, F fn)
 Sets the accelerations of all the world's bodies. More...
 
void SetAngle (Body &body, Angle value)
 Sets the body's angular orientation. More...
 
void SetAngle (World &world, BodyID id, Angle value)
 Sets the body's angular orientation. More...
 
void SetAngularDamping (Body &body, NonNegative< Frequency > value) noexcept
 Sets the angular damping of the body. More...
 
void SetAngularDamping (World &world, BodyID id, NonNegative< Frequency > angularDamping)
 Sets the angular damping of the body. More...
 
void SetAngularLimits (Joint &object, Angle lower, Angle upper)
 Sets the joint limits. More...
 
constexpr void SetAngularLimits (RevoluteJointConf &object, Angle lower, Angle upper) noexcept
 Free function for setting the angular limits of the given configuration.
 
void SetAngularLimits (World &world, JointID id, Angle lower, Angle upper)
 
void SetAngularOffset (Joint &object, Angle value)
 Sets the angular offset property of the specified joint if its type has one. More...
 
constexpr auto SetAngularOffset (MotorJointConf &object, Angle value) noexcept
 Free function for setting the angular offset value of the given configuration.
 
void SetAngularOffset (World &world, JointID id, Angle value)
 Sets the target angular offset. More...
 
void SetAwake (Body &body) noexcept
 Awakens this body. More...
 
void SetAwake (World &world, BodyID id)
 Wakes up the identified body. More...
 
void SetAwake (World &world, ContactID id)
 Sets awake the bodies of the given contact. More...
 
void SetAwake (World &world, JointID id)
 Wakes up the joined bodies. More...
 
void SetBeginContactListener (World &world, ContactFunction listener) noexcept
 Sets the begin-contact lister. More...
 
void SetBody (World &world, BodyID id, const Body &body)
 Sets the state of the identified body. More...
 
void SetContact (World &world, ContactID id, const Contact &value)
 Sets the identified contact's state. More...
 
constexpr auto SetCorrectionFactor (MotorJointConf &object, Real value) noexcept
 Free function for setting the correction factor value of the given configuration.
 
constexpr void SetDampingRatio (DistanceJointConf &object, Real value) noexcept
 Free function for setting the damping ratio value of the given configuration.
 
constexpr void SetDampingRatio (TargetJointConf &object, Real value) noexcept
 Free function for setting the damping ratio value of the given configuration.
 
constexpr void SetDampingRatio (WeldJointConf &object, Real value) noexcept
 Free function for setting the damping ratio of the given configuration.
 
constexpr void SetDampingRatio (WheelJointConf &object, Real value) noexcept
 Free function for setting the damping ratio of the given configuration.
 
void SetDensity (BaseShapeConf &arg, NonNegative< AreaDensity > value)
 Sets the density of the given shape configuration.
 
void SetDensity (Shape &shape, NonNegative< AreaDensity > value)
 Sets the density of the given shape. More...
 
void SetDensity (World &world, ShapeID id, NonNegative< AreaDensity > value)
 Sets the density of this shape. More...
 
constexpr void SetDestroyed (Body &body) noexcept
 Sets the destroyed property of the given body. More...
 
void SetDetachListener (World &world, BodyShapeFunction listener) noexcept
 Sets the detach listener for shapes detaching from bodies. More...
 
void SetEnabled (Body &body) noexcept
 Sets the enabled state. More...
 
void SetEnabled (Body &body, bool value) noexcept
 Sets the enabled state to the given value. More...
 
void SetEnabled (World &world, BodyID id, bool value)
 Sets the enabled state of the body. More...
 
void SetEnabled (World &world, ContactID id)
 Sets the enabled status of the identified contact. More...
 
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...
 
void SetEndContactListener (World &world, ContactFunction listener) noexcept
 Sets the end-contact lister. More...
 
void SetFilter (BaseShapeConf &arg, Filter value)
 Sets the filter of the given shape configuration.
 
void SetFilter (Shape &shape, Filter value)
 Sets the filter value for the given shape. More...
 
void SetFilterData (World &world, ShapeID id, const Filter &filter)
 Convenience function for setting the contact filtering data. More...
 
void SetFixedRotation (Body &body, bool value)
 Sets this body to have fixed rotation. More...
 
void SetFixedRotation (World &world, BodyID id, bool value)
 Sets this body to have fixed rotation. More...
 
void SetForce (World &world, BodyID id, const Force2 &force, const Length2 &point)
 Sets the given amount of force at the given point to the given body. More...
 
constexpr void SetFrequency (DistanceJointConf &object, NonNegative< Frequency > value) noexcept
 Free function for setting the frequency value of the given configuration.
 
void SetFrequency (Joint &object, Frequency value)
 Sets the frequency of the joint if it has this property. More...
 
constexpr void SetFrequency (TargetJointConf &object, NonNegative< Frequency > value) noexcept
 Free function for setting the frequency value of the given configuration.
 
constexpr void SetFrequency (WeldJointConf &object, NonNegative< Frequency > value) noexcept
 Free function for setting the frequency of the given configuration.
 
constexpr void SetFrequency (WheelJointConf &object, NonNegative< Frequency > value) noexcept
 Free function for setting the frequency of the given configuration.
 
void SetFrequency (World &world, JointID id, Frequency value)
 Sets the frequency of the identified joint if it has this property. More...
 
void SetFriction (BaseShapeConf &arg, NonNegative< Real > value)
 Sets the friction of the given shape.
 
void SetFriction (Shape &shape, NonNegative< Real > value)
 Sets the coefficient of friction. More...
 
void SetFriction (World &world, ContactID id, NonNegative< Real > friction)
 Sets the friction value for the identified contact. More...
 
void SetFriction (World &world, ShapeID id, NonNegative< Real > value)
 Convenience function for setting the coefficient of friction of the specified shape. More...
 
void SetImpenetrable (Body &body) noexcept
 Sets the impenetrable status of this body. More...
 
void SetImpenetrable (World &world, BodyID id)
 Sets 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...
 
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...
 
void SetJointDestructionListener (World &world, JointFunction listener) noexcept
 Sets the destruction listener for joints. More...
 
constexpr auto SetLength (DistanceJointConf &object, Length value) noexcept
 Free function for setting the length value of the given configuration.
 
void SetLinearDamping (Body &body, NonNegative< Frequency > value) noexcept
 Sets the linear damping of the body. More...
 
void SetLinearDamping (World &world, BodyID id, NonNegative< Frequency > linearDamping)
 Sets the linear damping of the body. More...
 
void SetLinearLimits (Joint &object, Length lower, Length upper)
 
constexpr void SetLinearLimits (PrismaticJointConf &conf, Length lower, Length upper) noexcept
 Free function for setting the linear limits of the given configuration.
 
void SetLinearOffset (Joint &object, const Length2 &value)
 Sets the linear offset property of the specified joint if its type has one. More...
 
constexpr auto SetLinearOffset (MotorJointConf &object, const Length2 &value) noexcept
 Free function for setting the linear offset value of the given configuration.
 
void SetLinearOffset (World &world, JointID id, const Length2 &value)
 Sets the target linear offset, in frame A. More...
 
void SetLocalCenter (Sweep &sweep, const Length2 &value) noexcept
 Convenience function for setting the sweep's local center.
 
void SetLocation (Body &body, const Length2 &value)
 Sets the body's location. More...
 
void SetLocation (World &world, BodyID id, const Length2 &value)
 Sets the body's location. More...
 
void SetManifold (World &world, ContactID id, const Manifold &value)
 Sets the identified manifold's state. More...
 
void SetMass (Body &body, Mass mass)
 Sets the mass of the given body.
 
void SetMassData (World &world, BodyID id, const MassData &massData)
 Sets the mass properties to override the mass properties of the fixtures. More...
 
constexpr void SetMaxForce (FrictionJointConf &object, NonNegative< Force > value) noexcept
 Free function for setting the max force value of the given configuration.
 
constexpr auto SetMaxForce (MotorJointConf &object, NonNegative< Force > value) noexcept
 Free function for setting the maximum force value of the given configuration.
 
constexpr auto SetMaxForce (TargetJointConf &object, NonNegative< Force > value) noexcept
 Free function for setting the maximum force value of the given configuration.
 
constexpr auto SetMaxLength (RopeJointConf &object, Length value) noexcept
 Free function for setting the maximum length value of the given configuration.
 
void SetMaxMotorForce (Joint &object, Force value)
 Sets the given joint's max motor force if its type supports that. More...
 
constexpr void SetMaxMotorForce (PrismaticJointConf &object, Force value)
 Free function for setting the maximum motor torque value of the given configuration.
 
void SetMaxMotorTorque (Joint &object, Torque value)
 Sets the given joint's max motor torque if its type supports that. More...
 
constexpr void SetMaxMotorTorque (RevoluteJointConf &object, Torque value)
 Free function for setting the max motor torque of the given configuration.
 
constexpr void SetMaxMotorTorque (WheelJointConf &object, Torque value) noexcept
 Sets the maximum motor torque for the given configuration.
 
void SetMaxMotorTorque (World &world, JointID id, Torque value)
 
constexpr auto SetMaxTorque (FrictionJointConf &object, NonNegative< Torque > value) noexcept
 Free function for setting the max force value of the given configuration.
 
constexpr auto SetMaxTorque (MotorJointConf &object, NonNegative< Torque > value) noexcept
 Free function for setting the maximum torque value of the given configuration.
 
void SetMotorSpeed (Joint &object, AngularVelocity value)
 Sets the given joint's motor speed if its type supports that. More...
 
template<typename T >
constexpr auto SetMotorSpeed (T &conf, AngularVelocity v) noexcept -> decltype(std::declval< T >().UseMotorSpeed(AngularVelocity{}))
 Sets the motor speed property of the given object.
 
void SetMotorSpeed (World &world, JointID id, AngularVelocity value)
 Sets the motor-speed property of the identied joint if it supports it. More...
 
void SetNormalImpulseAtPoint (VelocityConstraint &vc, VelocityConstraint::size_type index, Momentum value)
 Sets the normal impulse at the given point of the given velocity constraint.
 
void SetNormalImpulses (VelocityConstraint &vc, const Momentum2 &impulses)
 Sets the normal impulses of the given velocity constraint.
 
void SetPosition0 (Body &body, const Position &value) noexcept
 Sets the "position 0" Position information for the given body.
 
void SetPosition1 (Body &body, const Position &value) noexcept
 Sets the "position 1" Position information for the given body.
 
void SetPostSolveContactListener (World &world, ContactImpulsesFunction listener) noexcept
 Sets the post-solve-contact lister. More...
 
void SetPreSolveContactListener (World &world, ContactManifoldFunction listener) noexcept
 Sets the pre-solve-contact lister. More...
 
constexpr auto SetRatio (GearJointConf &object, Real value) noexcept
 Free function for setting the ratio value of the given configuration.
 
constexpr auto SetRatio (PulleyJointConf &object, Real value) noexcept
 Free function for setting the ratio value of the given configuration.
 
void SetRestitution (BaseShapeConf &arg, Real value) noexcept
 Sets the restitution of the given shape.
 
void SetRestitution (Shape &shape, Real value)
 Sets the coefficient of restitution value of the given shape. More...
 
void SetRestitution (World &world, ContactID id, Real restitution)
 Sets the restitution value for the specified contact. More...
 
void SetRestitution (World &world, ShapeID id, Real value)
 Sets the coefficient of restitution of the specified shape. More...
 
void SetRotInertia (Body &body, RotInertia value) noexcept
 Sets the rotational inertia of the body.
 
void SetSensor (BaseShapeConf &arg, bool value)
 Sets the is-sensor state of the given shape configuration.
 
void SetSensor (Shape &shape, bool value)
 Sets whether or not the given shape is a sensor. More...
 
void SetSensor (World &world, ShapeID id, bool value)
 Convenience function for setting whether the shape is a sensor or not. More...
 
void SetShape (World &world, ShapeID, const Shape &def)
 Sets the identified shape to the new value. More...
 
void SetShapeDestructionListener (World &world, ShapeFunction listener) noexcept
 Sets the destruction listener for shapes. More...
 
void SetSleepingAllowed (Body &body, bool value) noexcept
 
void SetSleepingAllowed (World &world, BodyID, bool value)
 Sets whether the identified body is allowed to sleep. More...
 
void SetSubStepping (World &world, bool flag) noexcept
 Enables/disables single stepped continuous physics. More...
 
void SetSweep (Body &body, const Sweep &value) noexcept
 Sets the sweep value of the given body. More...
 
void SetTangentImpulseAtPoint (VelocityConstraint &vc, VelocityConstraint::size_type index, Momentum value)
 Sets the tangent impulse at the given point of the given velocity constraint.
 
void SetTangentImpulses (VelocityConstraint &vc, const Momentum2 &impulses)
 Sets the tangent impulses of the given velocity constraint.
 
void SetTangentSpeed (World &world, ContactID id, LinearVelocity value)
 Sets the desired tangent speed for a conveyor belt behavior. More...
 
void SetTarget (Joint &object, const Length2 &value)
 Sets the given joint's target property if it has one. More...
 
constexpr void SetTarget (TargetJointConf &object, const Length2 &value) noexcept
 Free function for setting the target value of the given configuration.
 
void SetTarget (World &world, JointID id, const Length2 &value)
 Sets the target point. More...
 
void SetTorque (World &world, BodyID id, Torque torque)
 Sets the given amount of torque to the given body. More...
 
void SetTransform (World &world, BodyID id, const Length2 &location, Angle angle)
 Sets the position of the body's origin and rotation. More...
 
void SetTransformation (Body &body, const Transformation &value) noexcept
 Sets the body's transformation. More...
 
void SetTransformation (World &world, BodyID id, const Transformation &value)
 Sets the transformation of the body. More...
 
void SetType (Body &body, BodyType value) noexcept
 Sets the type of this body. More...
 
void SetType (World &world, BodyID id, BodyType value, bool resetMassData=true)
 Sets the type of the given body. More...
 
void SetVelocity (Body &body, AngularVelocity value) noexcept
 Sets the angular velocity. More...
 
void SetVelocity (Body &body, const LinearVelocity2 &value) noexcept
 Sets the linear velocity of the center of mass. More...
 
void SetVelocity (Body &body, const Velocity &value) noexcept
 Sets the body's velocity (linear and angular velocity). More...
 
void SetVelocity (World &world, BodyID id, AngularVelocity value)
 Sets the velocity of the identified body. More...
 
void SetVelocity (World &world, BodyID id, const LinearVelocity2 &value)
 Sets 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...
 
void SetVertexRadius (ChainShapeConf &arg, ChildCounter, NonNegative< Length > value) noexcept
 Sets the vertex radius of the shape for the given index.
 
void SetVertexRadius (ChainShapeConf &arg, NonNegative< Length > value) noexcept
 Sets the vertex radius of the shape.
 
void SetVertexRadius (DiskShapeConf &arg, ChildCounter, NonNegative< Length > value)
 Sets the vertex radius of shape for the given index.
 
void SetVertexRadius (EdgeShapeConf &arg, ChildCounter, NonNegative< Length > value)
 Sets the vertex radius of the shape for the given index.
 
void SetVertexRadius (EdgeShapeConf &arg, NonNegative< Length > value)
 Sets the vertex radius of the shape.
 
void SetVertexRadius (MultiShapeConf &arg, ChildCounter index, NonNegative< Length > value)
 Sets the vertex radius of shape for the given index.
 
void SetVertexRadius (PolygonShapeConf &arg, ChildCounter, NonNegative< Length > value)
 Sets the vertex radius of the shape for the given index.
 
void SetVertexRadius (PolygonShapeConf &arg, NonNegative< Length > value)
 Sets the vertex radius of the shape.
 
void SetVertexRadius (Shape &shape, ChildCounter idx, NonNegative< Length > value)
 Sets the vertex radius of the indexed child of the given shape. More...
 
constexpr bool ShiftOrigin (DistanceJointConf &, Length2) noexcept
 Shifts the origin notion of the given configuration.
 
constexpr bool ShiftOrigin (FrictionJointConf &, Length2) noexcept
 Shifts the origin notion of the given configuration.
 
constexpr bool ShiftOrigin (GearJointConf &, const Length2 &) noexcept
 Shifts the origin notion of the given configuration.
 
bool ShiftOrigin (Joint &object, const Length2 &value) noexcept
 Shifts the origin for any points stored in world coordinates. More...
 
constexpr auto ShiftOrigin (MotorJointConf &, const Length2 &) noexcept
 Shifts the origin notion of the given configuration.
 
constexpr auto ShiftOrigin (PrismaticJointConf &, const Length2 &) noexcept
 Shifts the origin notion of the given configuration.
 
bool ShiftOrigin (PulleyJointConf &object, const Length2 &newOrigin) noexcept
 Shifts the origin notion of the given configuration.
 
constexpr auto ShiftOrigin (RevoluteJointConf &, const Length2 &) noexcept
 Shifts the origin notion of the given configuration.
 
constexpr auto ShiftOrigin (RopeJointConf &, const Length2 &) noexcept
 Shifts the origin notion of the given configuration.
 
constexpr bool ShiftOrigin (TargetJointConf &object, const Length2 &newOrigin)
 Shifts the origin notion of the given configuration.
 
constexpr auto ShiftOrigin (WeldJointConf &, const Length2 &) noexcept
 Shifts the origin notion of the given configuration.
 
constexpr auto ShiftOrigin (WheelJointConf &, const Length2 &)
 Shifts the origin notion of the given configuration.
 
void ShiftOrigin (World &world, const Length2 &newOrigin)
 Shifts the origin of the specified world. More...
 
bool ShiftOrigin (World &world, JointID id, const Length2 &value)
 Shifts the origin of the identified joint. More...
 
bool ShouldCollide (const Shape &a, const Shape &b) noexcept
 Whether contact calculations should be performed between the two instances. More...
 
std::size_t size (const DynamicTree &tree) noexcept
 Gets the "size" of the given tree. More...
 
bool SolvePosition (const DistanceJointConf &object, const Span< BodyConstraint > &bodies, const ConstraintSolverConf &conf)
 Solves the position constraint. More...
 
bool SolvePosition (const FrictionJointConf &object, const Span< BodyConstraint > &bodies, const ConstraintSolverConf &conf)
 Solves the position constraint. More...
 
bool SolvePosition (const GearJointConf &object, const Span< BodyConstraint > &bodies, const ConstraintSolverConf &conf)
 Solves the position constraint. More...
 
bool SolvePosition (const Joint &object, const Span< BodyConstraint > &bodies, const ConstraintSolverConf &conf)
 Solves the position constraint. More...
 
bool SolvePosition (const MotorJointConf &object, const Span< BodyConstraint > &bodies, const ConstraintSolverConf &conf)
 Solves the position constraint. More...
 
bool SolvePosition (const PrismaticJointConf &object, const Span< BodyConstraint > &bodies, const ConstraintSolverConf &conf)
 Solves the position constraint. More...
 
bool SolvePosition (const PulleyJointConf &object, const Span< BodyConstraint > &bodies, const ConstraintSolverConf &conf)
 Solves the position constraint. More...
 
bool SolvePosition (const RevoluteJointConf &object, const Span< BodyConstraint > &bodies, const ConstraintSolverConf &conf)
 Solves the position constraint. More...
 
bool SolvePosition (const RopeJointConf &object, const Span< BodyConstraint > &bodies, const ConstraintSolverConf &conf)
 Solves the position constraint. More...
 
bool SolvePosition (const TargetJointConf &object, const Span< BodyConstraint > &bodies, const ConstraintSolverConf &conf)
 Solves the position constraint. More...
 
bool SolvePosition (const WeldJointConf &object, const Span< BodyConstraint > &bodies, const ConstraintSolverConf &conf)
 Solves the position constraint. More...
 
bool SolvePosition (const WheelJointConf &object, const Span< BodyConstraint > &bodies, const ConstraintSolverConf &conf)
 Solves the position constraint. More...
 
bool SolveVelocity (DistanceJointConf &object, const Span< BodyConstraint > &bodies, const StepConf &step)
 Solves velocity constraint. More...
 
bool SolveVelocity (FrictionJointConf &object, const Span< BodyConstraint > &bodies, const StepConf &step)
 Solves velocity constraint. More...
 
bool SolveVelocity (GearJointConf &object, const Span< BodyConstraint > &bodies, const StepConf &step)
 Solves velocity constraint. More...
 
bool SolveVelocity (Joint &object, const Span< BodyConstraint > &bodies, const StepConf &step)
 Solves velocity constraint. More...
 
bool SolveVelocity (MotorJointConf &object, const Span< BodyConstraint > &bodies, const StepConf &step)
 Solves velocity constraint. More...
 
bool SolveVelocity (PrismaticJointConf &object, const Span< BodyConstraint > &bodies, const StepConf &step)
 Solves velocity constraint. More...
 
bool SolveVelocity (PulleyJointConf &object, const Span< BodyConstraint > &bodies, const StepConf &step)
 Solves velocity constraint. More...
 
bool SolveVelocity (RevoluteJointConf &object, const Span< BodyConstraint > &bodies, const StepConf &step)
 Solves velocity constraint. More...
 
bool SolveVelocity (RopeJointConf &object, const Span< BodyConstraint > &bodies, const StepConf &step)
 Solves velocity constraint. More...
 
bool SolveVelocity (TargetJointConf &object, const Span< BodyConstraint > &bodies, const StepConf &step)
 Solves velocity constraint. More...
 
bool SolveVelocity (WeldJointConf &object, const Span< BodyConstraint > &bodies, const StepConf &step)
 Solves velocity constraint. More...
 
bool SolveVelocity (WheelJointConf &object, const Span< BodyConstraint > &bodies, const StepConf &step)
 Solves velocity constraint. More...
 
StepStats Step (World &world, const StepConf &conf=StepConf{})
 Steps the given world simulation according to the given configuration. More...
 
StepStats Step (World &world, Time delta, TimestepIters velocityIterations=StepConf::DefaultRegVelocityIters, TimestepIters positionIterations=StepConf::DefaultRegPositionIters)
 Steps the world ahead by a given time amount. More...
 
void swap (DynamicTree &lhs, DynamicTree &rhs) noexcept
 
Area TestOverlap (const DistanceProxy &proxyA, const Transformation &xfA, const DistanceProxy &proxyB, const Transformation &xfB, DistanceConf conf=DistanceConf{})
 Determine if two generic shapes overlap. More...
 
bool TestOverlap (const DynamicTree &tree, DynamicTree::Size leafIdA, DynamicTree::Size leafIdB) noexcept
 Tests for overlap of the elements identified in the given dynamic tree.
 
bool TestPoint (const DistanceProxy &proxy, const Length2 &point) noexcept
 Tests a point for containment in the given distance proxy. More...
 
bool TestPoint (const Shape &shape, const Length2 &point) noexcept
 Test a point for containment in the given shape. More...
 
bool TestPoint (const World &world, BodyID bodyId, ShapeID shapeId, const Length2 &p)
 Tests a point for containment in a shape associated with a body. More...
 
constexpr Length2 Transform (const Length2 &v, const Transformation &xfm) noexcept
 Transforms the given 2-D vector with the given transformation. More...
 
void Transform (PolygonShapeConf &arg, const Mat22 &m)
 Transforms the given polygon configuration's vertices by the given transformation matrix. More...
 
void Translate (ChainShapeConf &arg, const Length2 &value)
 Translates the given shape's vertices by the given amount.
 
void Translate (DiskShapeConf &arg, const Length2 &value) noexcept
 Translates the given shape configuration's vertices by the given amount.
 
void Translate (EdgeShapeConf &arg, const Length2 &value) noexcept
 Translates the given shape's vertices by the given amount.
 
void Translate (MultiShapeConf &arg, const Length2 &value)
 Translates the given shape configuration's vertices by the given amount.
 
void Translate (PolygonShapeConf &arg, const Length2 &value)
 Translates the given shape configuration's vertices by the given amount.
 
void Translate (Shape &shape, const Length2 &value)
 Translates all of the given shape's vertices by the given amount. More...
 
void Translate (World &world, ShapeID id, const Length2 &value)
 Translates all of the given shape's vertices by the given amount. More...
 
template<typename T >
TypeCast (const Joint &value)
 Converts the given joint into its current configuration value. More...
 
template<typename T >
std::add_pointer_t< std::add_const_t< T > > TypeCast (const Joint *value) noexcept
 Converts the given joint into its current configuration value. More...
 
template<typename T >
TypeCast (const Shape &value)
 Casts the specified instance into the template specified type. More...
 
template<typename T >
std::add_pointer_t< std::add_const_t< T > > TypeCast (const Shape *value) noexcept
 Converts the given shape into its current configuration value. More...
 
template<typename T >
TypeCast (const World &value)
 Converts the given joint into its current configuration value. More...
 
template<typename T >
std::add_pointer_t< std::add_const_t< T > > TypeCast (const World *value) noexcept
 Casts the given world into its current underlying configuration value. More...
 
template<typename T >
TypeCast (Joint &&value)
 Converts the given joint into its current configuration value. More...
 
template<typename T >
TypeCast (Joint &value)
 Converts the given joint into its current configuration value. More...
 
template<typename T >
std::add_pointer_t< T > TypeCast (Joint *value) noexcept
 Converts the given joint into its current configuration value. More...
 
template<typename T >
TypeCast (World &&value)
 Converts the given joint into its current configuration value. More...
 
template<typename T >
TypeCast (World &value)
 Converts the given joint into its current configuration value. More...
 
template<typename T >
std::add_pointer_t< T > TypeCast (World *value) noexcept
 Casts the given world into its current configuration value. More...
 
bool Unawaken (Body &body) noexcept
 Puts the body to sleep if it's awake. More...
 
void UnsetAwake (Body &body) noexcept
 Sets this body to asleep if sleeping is allowed. More...
 
void UnsetAwake (World &world, BodyID id)
 Sleeps the identified body. More...
 
constexpr void UnsetDestroyed (Body &body) noexcept
 Unsets the destroyed property of the given body. More...
 
void UnsetEnabled (Body &body) noexcept
 Unsets the enabled state. More...
 
void UnsetEnabled (World &world, ContactID id)
 Unsets the enabled status of the identified contact. More...
 
void UnsetImpenetrable (Body &body) noexcept
 Unsets the impenetrable status of this body. More...
 
void UnsetImpenetrable (World &world, BodyID id)
 Unsets the impenetrable status of the identified body. More...
 
bool Validate (const Span< const Length2 > &verts)
 Validates the convexity of the given collection of vertices. More...
 
bool ValidateMetrics (const DynamicTree &tree, DynamicTree::Size index) noexcept
 Validates the metrics of the given tree from the given index. More...
 
bool ValidateStructure (const DynamicTree &tree, DynamicTree::Size index) noexcept
 Validates the structure of the given tree from the given index. More...
 
AabbTreeWorld Listener Non-Member Functions
void SetShapeDestructionListener (AabbTreeWorld &world, ShapeFunction listener) noexcept
 Registers a destruction listener for shapes. More...
 
void SetDetachListener (AabbTreeWorld &world, BodyShapeFunction listener) noexcept
 Registers a detach listener for shapes detaching from bodies.
 
void SetJointDestructionListener (AabbTreeWorld &world, JointFunction listener) noexcept
 Register a destruction listener for joints. More...
 
void SetBeginContactListener (AabbTreeWorld &world, ContactFunction listener) noexcept
 Register a begin contact event listener.
 
void SetEndContactListener (AabbTreeWorld &world, ContactFunction listener) noexcept
 Register an end contact event listener.
 
void SetPreSolveContactListener (AabbTreeWorld &world, ContactManifoldFunction listener) noexcept
 Register a pre-solve contact event listener.
 
void SetPostSolveContactListener (AabbTreeWorld &world, ContactImpulsesFunction listener) noexcept
 Register a post-solve contact event listener.
 
AabbTreeWorld Miscellaneous Non-Member Functions
bool operator== (const AabbTreeWorld &lhs, const AabbTreeWorld &rhs)
 Equality operator for world comparisons.
 
bool operator!= (const AabbTreeWorld &lhs, const AabbTreeWorld &rhs)
 Inequality operator for world comparisons.
 
std::optional< pmr::StatsResource::StatsGetResourceStats (const AabbTreeWorld &world) noexcept
 Gets the resource statistics of the specified world.
 
void Clear (AabbTreeWorld &world) noexcept
 Clears this world. More...
 
StepStats Step (AabbTreeWorld &world, const StepConf &conf)
 Steps the world simulation according to the given configuration. More...
 
bool IsStepComplete (const AabbTreeWorld &world) noexcept
 Whether or not "step" is complete. More...
 
bool GetSubStepping (const AabbTreeWorld &world) noexcept
 Gets whether or not sub-stepping is enabled. More...
 
void SetSubStepping (AabbTreeWorld &world, bool flag) noexcept
 Enables/disables single stepped continuous physics. More...
 
const DynamicTreeGetTree (const AabbTreeWorld &world) noexcept
 Gets access to the broad-phase dynamic tree information.
 
bool IsLocked (const AabbTreeWorld &world) noexcept
 Is the world locked (in the middle of a time step).
 
void ShiftOrigin (AabbTreeWorld &world, const Length2 &newOrigin)
 Shifts the world origin. More...
 
Interval< Positive< Length > > GetVertexRadiusInterval (const AabbTreeWorld &world) noexcept
 Gets the vertex radius interval allowable for the given world. More...
 
Frequency GetInvDeltaTime (const AabbTreeWorld &world) noexcept
 Gets the inverse delta time. More...
 
const ProxyIDsGetProxies (const AabbTreeWorld &world) noexcept
 Gets the dynamic tree leaves queued for finding new contacts.
 
const BodyShapeIDsGetFixturesForProxies (const AabbTreeWorld &world) noexcept
 Gets the fixtures-for-proxies for this world. More...
 
AabbTreeWorld Body Member Functions

Member functions relating to bodies.

BodyCounter GetBodyRange (const AabbTreeWorld &world) noexcept
 Gets the extent of the currently valid body range. More...
 
const BodyIDsGetBodies (const AabbTreeWorld &world) noexcept
 Gets a container of valid world body identifiers for this constant world. More...
 
const BodyIDsGetBodiesForProxies (const AabbTreeWorld &world) noexcept
 Gets the bodies-for-proxies container for this world. More...
 
BodyID CreateBody (AabbTreeWorld &world, Body body=Body{})
 Creates a rigid body that's a copy of the given one. More...
 
const BodyGetBody (const AabbTreeWorld &world, BodyID id)
 Gets the identified body. More...
 
void SetBody (AabbTreeWorld &world, BodyID id, Body value)
 Sets the identified body. More...
 
void Destroy (AabbTreeWorld &world, BodyID id)
 Destroys the identified body. More...
 
auto IsDestroyed (const AabbTreeWorld &world, BodyID id) -> bool
 Gets whether the given identifier is to a body that's been destroyed. More...
 
const ProxyIDsGetProxies (const AabbTreeWorld &world, BodyID id)
 Gets the proxies for the identified body. More...
 
const BodyContactIDsGetContacts (const AabbTreeWorld &world, BodyID id)
 Gets the contacts associated with the identified body. More...
 
const BodyJointIDsGetJoints (const AabbTreeWorld &world, BodyID id)
 
AabbTreeWorld Joint Member Functions

Member functions relating to joints.

JointCounter GetJointRange (const AabbTreeWorld &world) noexcept
 Gets the extent of the currently valid joint range. More...
 
const JointIDsGetJoints (const AabbTreeWorld &world) noexcept
 Gets the container of joint IDs of the given world. More...
 
JointID CreateJoint (AabbTreeWorld &world, Joint def)
 Creates a joint to constrain one or more bodies. More...
 
const JointGetJoint (const AabbTreeWorld &world, JointID id)
 Gets the identified joint. More...
 
void SetJoint (AabbTreeWorld &world, JointID id, Joint def)
 Sets the identified joint. More...
 
void Destroy (AabbTreeWorld &world, JointID id)
 Destroys a joint. More...
 
auto IsDestroyed (const AabbTreeWorld &world, JointID id) -> bool
 Gets whether the given identifier is to a joint that's been destroyed. More...
 
AabbTreeWorld Shape Member Functions

Member functions relating to shapes.

ShapeCounter GetShapeRange (const AabbTreeWorld &world) noexcept
 Gets the extent of the currently valid shape range. More...
 
ShapeID CreateShape (AabbTreeWorld &world, Shape def)
 Creates an identifiable copy of the given shape within this world. More...
 
const ShapeGetShape (const AabbTreeWorld &world, ShapeID id)
 Gets the identified shape. More...
 
void SetShape (AabbTreeWorld &world, ShapeID id, Shape def)
 Sets the value of the identified shape. More...
 
void Destroy (AabbTreeWorld &world, ShapeID id)
 Destroys the identified shape removing any body associations with it first. More...
 
auto IsDestroyed (const AabbTreeWorld &world, ShapeID id) -> bool
 Gets whether the given identifier is to a shape that's been destroyed. More...
 
AabbTreeWorld Contact Member Functions

Member functions relating to contacts.

ContactCounter GetContactRange (const AabbTreeWorld &world) noexcept
 Gets the extent of the currently valid contact range. More...
 
KeyedContactIDs GetContacts (const AabbTreeWorld &world)
 Gets a container of valid world contact identifiers. More...
 
const ContactGetContact (const AabbTreeWorld &world, ContactID id)
 Gets the identified contact. More...
 
void SetContact (AabbTreeWorld &world, ContactID id, Contact value)
 Sets the identified contact's state. More...
 
const ManifoldGetManifold (const AabbTreeWorld &world, ContactID id)
 Gets the identified manifold. More...
 
void SetManifold (AabbTreeWorld &world, ContactID id, const Manifold &value)
 Sets the identified manifold. More...
 
auto IsDestroyed (const AabbTreeWorld &world, ContactID id) -> bool
 Gets whether the given identifier is to a contact that's been destroyed. More...
 

Variables

constexpr auto EarthlyGravity = LinearAcceleration2{0_mps2, EarthlyLinearAcceleration}
 Earthly gravity in 2-dimensions. More...
 
constexpr auto InvalidAABB
 Invalid AABB value. More...
 
template<class T >
constexpr bool IsValidJointTypeV = detail::IsValidJointType<T>::value
 Boolean value for whether the specified type is a valid joint type. More...
 
constexpr auto Transform_identity
 Identity transformation value. More...
 

Detailed Description

Name space for 2-dimensionally related PlayRho names.

Typedef Documentation

◆ DynamicTreeRayCastCB

using playrho::d2::DynamicTreeRayCastCB = typedef std::function<Real(BodyID body, ShapeID shape, ChildCounter child, const RayCastInput& input)>

Ray cast callback function.

Note
Return 0 to terminate ray casting, or > 0 to update the segment bounding box.

◆ JointIDs

using playrho::d2::JointIDs = typedef std::vector<JointID>

Joint IDs container type.

Note
Cannot be container of Joint instances since joints are polymorphic types.

◆ QueryShapeCallback

using playrho::d2::QueryShapeCallback = typedef std::function<bool(BodyID body, ShapeID shape, ChildCounter child)>

Query AABB for fixtures callback function type.

Note
Returning true will continue the query. Returning false will terminate the query.

◆ RayCastOutput

using playrho::d2::RayCastOutput = typedef std::optional<RayCastHit>

Ray cast output.

This is a type alias for an optional RayCastHit instance.

See also
RayCast, RayCastHit

Function Documentation

◆ Advance()

void playrho::d2::Advance ( Body body,
ZeroToUnderOneFF< Real value 
)
inlinenoexcept

Advances the body by a given time ratio.

This function:

  1. advances the body's sweep to the given time ratio;
  2. updates the body's sweep positions (linear and angular) to the advanced ones; and
  3. updates the body's transform to the new sweep one settings.
    Parameters
    bodyThe body to update.
    valueValid new time factor in [0,1) to advance the sweep to.
    See also
    GetSweep, SetSweep, GetTransofmration, SetTransformation.

◆ Advance0() [1/2]

void playrho::d2::Advance0 ( Body body,
ZeroToUnderOneFF< Real value 
)
inlinenoexcept

Calls the body sweep's Advance0 function to advance to the given value.

See also
GetSweep.

Referenced by Advance(), and playrho::d2::Body::Advance0().

◆ Advance0() [2/2]

Sweep playrho::d2::Advance0 ( const Sweep sweep,
ZeroToUnderOneFF< Real alpha 
)
noexcept

Advances the sweep by a factor of the difference between the given time alpha and the sweep's alpha 0.

This advances position 0 (pos0) of the sweep towards position 1 (pos1) by a factor of the difference between the given alpha and the alpha 0. This does not change the sweep's position 1.

Parameters
sweepThe sweep to return an advancement of.
alphaValid new time factor in [0,1) to update the sweep to.

◆ ApplyAngularImpulse() [1/2]

void playrho::d2::ApplyAngularImpulse ( Body body,
AngularMomentum  impulse 
)
noexcept

Applies an angular impulse.

Parameters
bodyBody to apply the angular impulse to.
impulseAngular impulse to be applied.
Examples
WorldBody.cpp.

Referenced by playrho::d2::World::ApplyAngularImpulse().

◆ ApplyAngularImpulse() [2/2]

void playrho::d2::ApplyAngularImpulse ( World world,
BodyID  id,
AngularMomentum  impulse 
)

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
WrongStateif this function is called while the world is locked.
std::out_of_rangeIf given an invalid body identifier.

◆ ApplyForce()

void playrho::d2::ApplyForce ( World world,
BodyID  id,
const Force2 force,
const Length2 point 
)

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
WrongStateif this function is called while the world is locked.
std::out_of_rangeIf given an invalid body identifier.
Examples
WorldBody.cpp.

◆ ApplyForceToCenter()

void ApplyForceToCenter ( World world,
BodyID  id,
const Force2 force 
)
inline

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
WrongStateif this function is called while the world is locked.
std::out_of_rangeIf given an invalid body identifier.
Examples
World.cpp.

◆ ApplyLinearImpulse() [1/2]

void playrho::d2::ApplyLinearImpulse ( Body body,
const Momentum2 impulse,
const Length2 point 
)
noexcept

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
bodyBody to apply the impulse to.
impulsethe world impulse vector.
pointthe world position of the point of application.
Examples
WorldBody.cpp.

Referenced by playrho::d2::World::ApplyLinearImpulse().

◆ ApplyLinearImpulse() [2/2]

void playrho::d2::ApplyLinearImpulse ( World world,
BodyID  id,
const Momentum2 impulse,
const Length2 point 
)

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
WrongStateif this function is called while the world is locked.
std::out_of_rangeIf given an invalid body identifier.

◆ ApplyTorque()

void playrho::d2::ApplyTorque ( World world,
BodyID  id,
Torque  torque 
)

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
WrongStateif this function is called while the world is locked.
std::out_of_rangeIf given an invalid body identifier.
Examples
WorldBody.cpp.

◆ Attach() [1/3]

void playrho::d2::Attach ( AabbTreeWorld world,
BodyID  id,
ShapeID  shapeID 
)

Associates a validly identified shape with the validly identified body.

Exceptions
std::out_of_rangeIf given an invalid body or shape identifier.
WrongStateif this function is called while the world is locked.
See also
GetShapes.
Examples
DistanceJoint.cpp, FrictionJoint.cpp, GearJoint.cpp, MotorJoint.cpp, PrismaticJoint.cpp, RevoluteJoint.cpp, RopeJoint.cpp, WeldJoint.cpp, WheelJoint.cpp, World.cpp, WorldBody.cpp, WorldContact.cpp, and WorldShape.cpp.

Referenced by playrho::d2::World::Attach().

◆ Attach() [2/3]

void playrho::d2::Attach ( World world,
BodyID  id,
const Shape shape,
bool  resetMassData = true 
)

Creates the shape within the world and then associates it with the validly identified body.

Exceptions
std::out_of_rangeIf given an invalid body.
WrongStateif this function is called while the world is locked.
See also
GetShapes, ResetMassData.

◆ Attach() [3/3]

void playrho::d2::Attach ( World world,
BodyID  id,
ShapeID  shapeID,
bool  resetMassData = true 
)

Associates a validly identified shape with the validly identified body.

Note
This function should not be called if the world is locked.
Exceptions
std::out_of_rangeIf given an invalid body or shape identifier.
WrongStateif this function is called while the world is locked.
See also
GetShapes, ResetMassData.

◆ Awaken() [1/3]

bool Awaken ( Body body)
inlinenoexcept

Awakens the body if it's asleep.

See also
Unawaken(Body& body).
Examples
World.cpp, and WorldBody.cpp.

Referenced by playrho::d2::World::Awaken().

◆ Awaken() [2/3]

BodyCounter playrho::d2::Awaken ( World world)

Awakens all of the "speedable" bodies in the given world.

Convenience function for calling Awaken(World&, BodyID) for all bodies identified in the given world.

Parameters
worldThe world whose bodies are to be awoken.
Returns
Sum total of calls to Awaken(World&, BodyID) that returned true.
Postcondition
On normal return: IsAwake(const World&, BodyID) returns true for all the "speedable" bodies of the given world.
See also
GetBodies(const World&), Awaken(World&, BodyID), IsAwake(const World&, BodyID), IsSpeedable(BodyType).

◆ Awaken() [3/3]

bool Awaken ( World world,
BodyID  id 
)
inline

Awakens the body if it's asleep and "speedable".

Parameters
worldThe world for which the identified body is to be awoken.
idIdentifier of the body within the world to awaken.
Returns
true if SetAwake(World&, BodyID) was called on the identified body, false otherwise.
Exceptions
WrongStateif this function is called while the world is locked.
std::out_of_rangeIf given an invalid body identifier.
Postcondition
On returning true: IsAwake(const World&, BodyID) returns true for the given world and identified body.
See also
IsAwake(const World&, BodyID), IsSpeedable(BodyType), GetType(const World&, BodyID), SetAwake(World&, BodyID).

◆ CalcGravitationalAcceleration()

Acceleration playrho::d2::CalcGravitationalAcceleration ( const World world,
BodyID  id 
)

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.
Examples
WorldBody.cpp.

◆ CalcSearchDirection()

Length2 playrho::d2::CalcSearchDirection ( const SimplexEdges simplexEdges)
noexcept

Calculates the "search direction" for the given simplex edge list.

Parameters
simplexEdgesA one or two edge list.
Warning
Behavior is not specified if the given edge list has zero edges.
Returns
"search direction" vector.

Referenced by playrho::d2::DistanceProxy::Distance().

◆ Cap()

Velocity playrho::d2::Cap ( Velocity  velocity,
Time  h,
const MovementConf conf 
)
noexcept

Caps velocity.

Enforces maximums on the given velocity.

Parameters
velocityVelocity to cap.
hTime elapsed to get velocity for.
confMovement configuration. This defines caps on linear and angular speeds.

◆ Clear() [1/2]

void playrho::d2::Clear ( AabbTreeWorld world)
noexcept

Clears this world.

Note
This calls the joint and shape destruction listeners (if they're set), for all defined joints and shapes, before clearing anything. Any exceptions thrown from these listeners are ignored.
Postcondition
The contents of this world have all been destroyed and this world's internal state reset as though it had just been constructed.
See also
SetJointDestructionListener, SetShapeDestructionListener.
Examples
World.cpp, WorldBody.cpp, and WorldShape.cpp.

Referenced by playrho::d2::detail::WorldModel< T >::Clear_().

◆ Clear() [2/2]

void playrho::d2::Clear ( World world)
inlinenoexcept

Clears the given world.

Note
This calls the joint and shape destruction listeners (if they're set), for all defined joints and shapes, before clearing anything. Any exceptions thrown from these listeners are ignored.
Parameters
worldThe world to clear.
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.
See also
SetJointDestructionListener, SetShapeDestructionListener.

◆ ClearForces()

void ClearForces ( World world)
inline

Clears forces.

Manually clear the force buffer on all bodies.

Exceptions
WrongStateif this function is called while the world is locked.
Examples
World.cpp.

◆ CollideShapes()

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

Calculates the relevant collision manifold.

Note
The returned touching state information typically agrees with that returned from the distance-proxy-based TestOverlap function. This is not always the case however especially when the separation or overlap distance is closer to zero.
Examples
Shape.cpp.

◆ ComputeAABB() [1/4]

AABB playrho::d2::ComputeAABB ( const DistanceProxy proxy,
const Transformation xf 
)
noexcept

Computes the AABB.

Computes the Axis Aligned Bounding Box (AABB) for the given child shape at a given a transform.

Parameters
proxyDistance proxy for the child shape.
xfWorld transform of the shape.
Precondition
xf is valid.
Returns
AABB for the proxy shape or the default AABB if the proxy has a zero vertex count.
Examples
World.cpp.

Referenced by playrho::d2::Shape::ComputeAABB(), playrho::d2::World::ComputeAABB(), and playrho::d2::World::ComputeIntersectingAABB().

◆ ComputeAABB() [2/4]

AABB playrho::d2::ComputeAABB ( const DistanceProxy proxy,
const Transformation xfm0,
const Transformation xfm1 
)
noexcept

Computes the AABB.

Computes the Axis Aligned Bounding Box (AABB) for the given child shape at the given transforms.

Parameters
proxyDistance proxy for the child shape.
xfm0World transform 0 of the shape.
xfm1World transform 1 of the shape.
Precondition
xfm0 and xfm1 are both valid.
Returns
AABB for the proxy shape or the default AABB if the proxy has a zero vertex count.

◆ ComputeAABB() [3/4]

AABB playrho::d2::ComputeAABB ( const World world,
BodyID  bodyID,
ShapeID  shapeID 
)

Computes the AABB for the identified shape relative to the identified body within the given world.

Parameters
worldThe world in which the given body and shape identifiers identify a body and shape.
bodyIDIdentifier of the body the identified shape is associated with.
shapeIDIdentifier of the shape associated with the identified body to compute the AABB for.
See also
ComputeAABB(const World&, BodyID).

◆ ComputeAABB() [4/4]

AABB playrho::d2::ComputeAABB ( const World world,
BodyID  id 
)

Computes the AABB for the identified body within the given world.

Parameters
worldThe world in which the given body identifier identifies a body.
idIdentifier of the body to compute the AABB for.
See also
ComputeAABB(const World&, BodyID, ShapeID).

◆ ComputeHeight()

DynamicTree::Height playrho::d2::ComputeHeight ( const DynamicTree tree,
DynamicTree::Size  index 
)
noexcept

Computes the height of the tree from a given node.

Parameters
treeTree to compute the height at the given node for.
indexID of node to compute height from.
Precondition
index is less than tree.GetNodeCapacity().
Returns
0 unless the given index is to a branch node.

Referenced by ComputeHeight().

◆ ComputeIntersectingAABB() [1/2]

AABB playrho::d2::ComputeIntersectingAABB ( const World world,
BodyID  bA,
ShapeID  sA,
ChildCounter  iA,
BodyID  bB,
ShapeID  sB,
ChildCounter  iB 
)

Computes the intersecting AABB for the given pair of body-shape-index values.

The intersecting AABB for the given pair of body-shape-index values is the intersection of the AABB for child A of shape A of body A with the AABB for child B of shape B of body B.

Referenced by playrho::d2::World::ComputeIntersectingAABB().

◆ ComputeIntersectingAABB() [2/2]

AABB playrho::d2::ComputeIntersectingAABB ( const World world,
const Contact contact 
)

Computes the intersecting AABB for the given contact.

Parameters
worldThe world for which the given contact relates to.
contactThe contact identifying bodies, shapes, and children with world to compute the intersecting AABB for.

◆ ComputeMassData() [1/2]

MassData playrho::d2::ComputeMassData ( const World world,
BodyID  id 
)

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.

Referenced by playrho::d2::World::ComputeMassData(), and playrho::d2::World::ResetMassData().

◆ ComputeMassData() [2/2]

MassData playrho::d2::ComputeMassData ( const World world,
const Span< const ShapeID > &  ids 
)

Computes the mass data total of the identified shapes.

This basically accumulates the mass data over all shapes.

Note
The center is the mass weighted sum of all shape centers. Divide it by the mass to get the averaged center.
Returns
accumulated mass data for all shapes identified.
Exceptions
std::out_of_rangeIf given an invalid shape identifier.

◆ ComputePerimeterRatio()

Real playrho::d2::ComputePerimeterRatio ( const DynamicTree tree)
noexcept

Gets the ratio of the sum of the perimeters of nodes to the root perimeter.

Note
Zero is returned if no proxies exist at the time of the call.
Returns
Value of zero or more.
Examples
World.cpp.

◆ ComputeTotalPerimeter()

Length playrho::d2::ComputeTotalPerimeter ( const DynamicTree tree)
noexcept

Gets the sum of the perimeters of nodes.

Note
Zero is returned if no proxies exist at the time of the call.
Returns
Value of zero or more.

Referenced by ComputePerimeterRatio().

◆ CreateBody() [1/3]

BodyID playrho::d2::CreateBody ( AabbTreeWorld world,
Body  body = Body{} 
)

Creates a rigid body that's a copy of the given one.

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.
This function does not reset the mass data for the body.
Postcondition
The created body will be present in the container returned from the GetBodies(const AabbTreeWorld&) function.
Parameters
worldThe world within which to create the body.
bodyA customized body or its default value.
Returns
Identifier of the newly created body which can later be destroyed by calling the Destroy(BodyID) function.
Exceptions
WrongStateif this function is called while the world is locked.
LengthErrorif this operation would create more than MaxBodies.
std::out_of_rangeif the given body references any invalid shape identifiers.
See also
Destroy(BodyID), GetBodies.
Physical Entities.
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 WorldShape.cpp.

Referenced by playrho::d2::AabbTreeWorld::CreateBody(), playrho::d2::World::CreateBody(), and playrho::d2::detail::WorldModel< T >::CreateBody_().

◆ CreateBody() [2/3]

BodyID playrho::d2::CreateBody ( World world,
const Body body = Body{},
bool  resetMassData = true 
)

Creates a rigid body within the world that's a copy of the given one.

Note
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.
No references to the configuration are retained. Its value is copied.
Parameters
worldThe world within which to create the body.
bodyA customized body or its default value.
resetMassDataWhether or not the mass data of the body should be reset.
Returns
Identifier of the newly created body which can later be destroyed by calling the Destroy(BodyID) function.
Exceptions
WrongStateif this function is called while the world is locked.
LengthErrorif this operation would create more than MaxBodies.
std::out_of_rangeif the given body references any out of range shape identifiers.
Postcondition
The created body's identifier will be present in the container returned from the GetBodies(const World&) function.
Calling GetBody(const World&, BodyID) with the returned body identifer returns the body given to this create function.
See also
Destroy(World& world, BodyID), GetBodies(const World&), ResetMassData, GetShapeRange.
Physical Entities.

◆ CreateBody() [3/3]

BodyID playrho::d2::CreateBody ( World world,
const BodyConf def,
bool  resetMassData = true 
)

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&) function.
Parameters
worldThe world within which to create the body.
defA customized body configuration or its default value.
resetMassDataWhether or not the mass data of the body should be reset.
Returns
Identifier of the newly created body which can later be destroyed by calling the Destroy(World&, BodyID) function.
Exceptions
WrongStateif this function is called while the world is locked.
LengthErrorif this operation would create more than MaxBodies.
See also
Destroy(World& world, BodyID), GetBodies(const World&), ResetMassData.
Physical Entities.

◆ CreateJoint() [1/3]

JointID playrho::d2::CreateJoint ( AabbTreeWorld world,
Joint  def 
)

Creates a joint to constrain one or more bodies.

Warning
This function is locked during callbacks.
Note
No references to the configuration are retained. Its value is copied.
Postcondition
The created joint will be present in the container returned from the GetJoints(const AabbTreeWorld&) function.
Returns
Identifier for the newly created joint which can later be destroyed by calling the Destroy(JointID) function.
Exceptions
WrongStateif this function is called while the world is locked.
LengthErrorif this operation would create more than MaxJoints.
InvalidArgumentif the given definition is not allowed.
std::out_of_rangeif the given joint references any invalid body id.
See also
Physical Entities.
Destroy(JointID), GetJoints.
Examples
DistanceJoint.cpp, FrictionJoint.cpp, GearJoint.cpp, MotorJoint.cpp, PrismaticJoint.cpp, PulleyJoint.cpp, RevoluteJoint.cpp, RopeJoint.cpp, WeldJoint.cpp, WheelJoint.cpp, and World.cpp.

Referenced by playrho::d2::World::CreateJoint(), and playrho::d2::detail::WorldModel< T >::CreateJoint_().

◆ CreateJoint() [2/3]

JointID playrho::d2::CreateJoint ( World world,
const Joint def 
)
inline

Creates a new joint within the given world.

Parameters
worldThe world in which the specified joint is to be created within.
defState of the joint to create within the world.
Exceptions
WrongStateif this function is called while the world is locked.
Postcondition
On success: GetJoints(const World&) for this same world will contain the identifier returned by this function; GetJoint(const World&, JointID) for world and the returned identifier, returns def .

◆ CreateJoint() [3/3]

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

Creates a new joint from a configuration.

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

Exceptions
WrongStateif this function is called while the world is locked.

◆ CreateShape() [1/3]

ShapeID playrho::d2::CreateShape ( AabbTreeWorld world,
Shape  def 
)

Creates an identifiable copy of the given shape within this world.

Exceptions
InvalidArgumentif called for a shape with a vertex radius that's not within the world's allowable vertex radius interval.
WrongStateif this function is called while the world is locked.
LengthErrorif this operation would create more than MaxShapes.
See also
Destroy(ShapeID), GetShape, SetShape, GetVertexRadiusInterval(const AabbTreeWorld& world).
Examples
DistanceJoint.cpp, FrictionJoint.cpp, GearJoint.cpp, HelloWorld.cpp, MotorJoint.cpp, PrismaticJoint.cpp, RevoluteJoint.cpp, RopeJoint.cpp, WeldJoint.cpp, WheelJoint.cpp, World.cpp, WorldBody.cpp, WorldContact.cpp, and WorldShape.cpp.

Referenced by playrho::d2::World::Attach(), and playrho::d2::detail::WorldModel< T >::CreateShape_().

◆ CreateShape() [2/3]

ShapeID playrho::d2::CreateShape ( World world,
const Shape def 
)
inline

Creates an identifiable copy of the given shape within the specified world.

Exceptions
InvalidArgumentif called for a shape with a vertex radius that's not within the world's allowable vertex radius interval.
WrongStateif this function is called while the world is locked.
LengthErrorif this operation would create more than MaxShapes.
See also
Destroy(World&, ShapeID), GetShape, SetShape, GetVertexRadiusInterval.

◆ CreateShape() [3/3]

template<typename T >
auto CreateShape ( World world,
const T &  shapeConf 
) -> decltype(CreateShape(world, Shape{shapeConf}))

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

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

Exceptions
InvalidArgumentif called for a shape with a vertex radius that's not within the world's allowable vertex radius interval.
WrongStateif called while the world is "locked".
See also
CreateShape(World& world, const Shape& def), GetVertexRadiusInterval.

◆ Destroy() [1/6]

void playrho::d2::Destroy ( AabbTreeWorld world,
BodyID  id 
)

Destroys the identified body.

Destroys a given body that had previously been created by a call to this world's CreateBody(const Body&) function.

Warning
This automatically deletes all associated shapes and joints.
Note
This function is locked during callbacks.
Parameters
worldThe world within which the identified body is to be destroyed.
idIdentifier of body to destroy that had been created by this world.
Exceptions
WrongStateif this function is called while the world is locked.
std::out_of_rangeIf given an invalid body identifier.
Postcondition
On success: the destroyed body will no longer be present in the container returned from the GetBodies(const AabbTreeWorld&) function; none of the body's fixtures will be present in the fixtures-for-proxies collection; IsDestroyed(const AabbTreeWorld& world, BodyID) for world and id returns true.
See also
CreateBody, GetBodies(const AabbTreeWorld&), GetFixturesForProxies, IsDestroyed(const AabbTreeWorld& world, BodyID).
Physical Entities.
Examples
RevoluteJoint.cpp, World.cpp, WorldBody.cpp, and WorldShape.cpp.

Referenced by playrho::d2::detail::WorldModel< T >::Destroy_().

◆ Destroy() [2/6]

void playrho::d2::Destroy ( AabbTreeWorld world,
JointID  id 
)

Destroys a joint.

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

Note
This function is locked during callbacks.
This may cause the connected bodies to begin colliding.
Parameters
worldThe world within which the identified joint is to be destroyed.
idIdentifier of joint to destroy that had been created by this world.
Postcondition
On success: the destroyed joint will no longer be present in the container returned from the GetJoints(const AabbTreeWorld&) function; IsDestroyed(const AabbTreeWorld&,JointID) returns true.
Exceptions
WrongStateif this function is called while the world is locked.
See also
CreateJoint, GetJoints, IsDestroyed(const AabbTreeWorld& world, JointID).
Physical Entities.

◆ Destroy() [3/6]

void playrho::d2::Destroy ( AabbTreeWorld world,
ShapeID  id 
)

Destroys the identified shape removing any body associations with it first.

Note
This function is locked during callbacks.
This function does not reset the mass data of any effected bodies.
Parameters
worldThe world from which the identified shape is to be destroyed.
idIdentifier of the shape to destroy.
Exceptions
WrongStateif this function is called while the world is locked.
std::out_of_rangeIf given an invalid shape identifier.
Postcondition
On success: IsDestroyed(const AabbTreeWorld& world, ShapeID) for world and id returns true.
See also
CreateShape, Detach, IsDestroyed(const AabbTreeWorld& world, ShapeID).

◆ Destroy() [4/6]

void playrho::d2::Destroy ( World world,
BodyID  id 
)
inline

Destroys the identified body.

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

Note
This automatically deletes all associated shapes and joints.
This function is locked during callbacks. The detatch listener, if set, is called for every shape associated with the identified body.
Parameters
worldThe world from which to delete the identified body from.
idIdentifier of body to destroy that had been created in world.
Exceptions
WrongStateif this function is called while the world is locked.
std::out_of_rangeIf given an out of range body identifier.
Postcondition
On success: the destroyed body's identifier is no longer present in the container returned from the GetBodies(const World&) function; the count returned by GetBodyCount(const World&) will be one less than before this was called; GetBodyRange(const World&) will be unchanged.
See also
CreateBody, GetBodies, GetBodyCount, GetBodyRange, SetDetachListener, IsLocked.
Physical Entities.

◆ Destroy() [5/6]

void playrho::d2::Destroy ( World world,
JointID  id 
)
inline

Destroys the identified joint.

Parameters
worldThe world in which the specified joint is to be destroyed from.
idIdentifier of the joint to destroy.
Exceptions
WrongStateif this function is called while the world is locked.
std::out_of_rangeIf given an out of range joint identifier.
Postcondition
On success: the given identifier is no longer within those returned by GetJoints(const World&), the count returned by GetJointCount(const World&) will be one less than before this was called.
See also
CreateJoint, IsLocked, GetJointRange.

◆ Destroy() [6/6]

void playrho::d2::Destroy ( World world,
ShapeID  id 
)
inline

Destroys the identified shape.

Parameters
worldThe world in which the specified shape is to be destroyed from.
idIdentifier of the shape to destroy.
Exceptions
WrongStateif this function is called while the world is locked.
std::out_of_rangeIf given an out of range identifier.
Postcondition
On success: no body in the specified world will have the identified shape attached to it; GetShapeRange(const World&) will be unchanged.
See also
CreateShape, IsLocked, GetShapeRange.

◆ Detach() [1/3]

bool playrho::d2::Detach ( AabbTreeWorld world,
BodyID  id,
ShapeID  shapeID 
)

Disassociates a validly identified shape from the validly identified body.

Exceptions
std::out_of_rangeIf given an invalid body or shape identifier.
WrongStateif this function is called while the world is locked.
Examples
World.cpp, WorldBody.cpp, and WorldShape.cpp.

Referenced by playrho::d2::World::Detach().

◆ Detach() [2/3]

bool playrho::d2::Detach ( World world,
BodyID  id,
bool  resetMassData = true 
)

Disassociates all of the associated shape from the validly identified body.

Exceptions
std::out_of_rangeIf given an invalid body identifier.
WrongStateif this function is called while the world is locked.
See also
Attach, ResetMassData.

◆ Detach() [3/3]

bool playrho::d2::Detach ( World world,
BodyID  id,
ShapeID  shapeID,
bool  resetMassData = true 
)

Disassociates a validly identified shape from the validly identified body.

Exceptions
std::out_of_rangeIf given an invalid body or shape identifier.
WrongStateif this function is called while the world is locked.
See also
ResetMassData.

◆ Distance()

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

Determines the closest points between two shapes using an iterative method.

Note
Supports any combination of convex shapes.
Uses the G.J.K. (GJK) algorithm: "a method for determining the minimum distance between two convex sets".
On the first call, size(conf.cache.indices) should be zero.
Parameters
proxyAProxy A.
transformATransform of A.
proxyBProxy B.
transformBTransform of B.
confConfiguration to use including the simplex cache for assisting the determination.
Returns
Closest points between the two shapes, the count of iterations it took to determine them, and the reason iterations stopped. The iteration count will always be greater than zero unless DefaultMaxDistanceIters is zero.
See also
https://en.wikipedia.org/wiki/Gilbert%2DJohnson%2DKeerthi_distance_algorithm
GetMaxSeparation.

Referenced by playrho::ToiOutput::GetToiViaSat(), and playrho::d2::DistanceProxy::TestOverlap().

◆ EnableLimit() [1/2]

void playrho::d2::EnableLimit ( Joint object,
bool  value 
)

Enables the specified joint's limit property if it supports one.

Exceptions
std::invalid_argumentIf not supported for the given joint's type.
Examples
Joint.cpp, PrismaticJoint.cpp, and RevoluteJoint.cpp.

Referenced by playrho::d2::World::EnableLimit().

◆ EnableLimit() [2/2]

void playrho::d2::EnableLimit ( World world,
JointID  id,
bool  value 
)

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

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

◆ EnableMotor() [1/2]

void playrho::d2::EnableMotor ( Joint object,
bool  value 
)

Enables the specified joint's motor property if it supports one.

Exceptions
std::invalid_argumentIf not supported for the given joint's type.
Examples
Joint.cpp, PrismaticJoint.cpp, RevoluteJoint.cpp, and WheelJoint.cpp.

Referenced by playrho::d2::World::EnableMotor().

◆ EnableMotor() [2/2]

void playrho::d2::EnableMotor ( World world,
JointID  id,
bool  value 
)

Enable/disable the joint motor.

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

◆ Evaluate()

Length playrho::d2::Evaluate ( const SeparationScenario scenario,
const DistanceProxy proxyA,
const Transformation xfA,
const DistanceProxy proxyB,
const Transformation xfB,
IndexPair  indexPair 
)

Evaluates the separation of the identified proxy vertices at the given time factor.

Parameters
scenarioSeparation scenario to evaluate.
proxyAInterface to data for convex polygon A.
xfATransformation A.
proxyBInterface to data for convex polygon B.
xfBTransformation B.
indexPairIndexes of the proxy A and proxy B vertexes.
Returns
Separation distance which will be negative when the given transforms put the vertices on the opposite sides of the separating axis.

Referenced by playrho::ToiOutput::GetToiViaSat().

◆ FindClosestBody()

BodyID playrho::d2::FindClosestBody ( const World world,
const Length2 location 
)

Finds body in given world that's closest to the given location.

Parameters
worldThe world to find closest body to location in.
locationLocation in the given world to find the closest body to.
Returns
Identifier of the closest body, or InvalidBodyID.
Examples
World.cpp.

◆ FindIndex()

auto playrho::d2::FindIndex ( const DynamicTree tree,
const Contactable c 
) -> DynamicTree::Size
noexcept

Finds index of node matching given contactble using a linear search.

Returns
Node index or DynamicTree::InvalidSize.
See also
DynamicTree::InvalidSize.
Examples
World.cpp.

◆ FindLowestRightMostVertex()

std::size_t playrho::d2::FindLowestRightMostVertex ( Span< const Length2 vertices)
noexcept

Finds the index of the lowest right most vertex in the given collection.

Returns
Index of the lowest right most vertex in the given collection, or std::size_t(-1) for empty container.

Referenced by GetConvexHullAsVector().

◆ FindMinSeparation()

LengthIndexPair playrho::d2::FindMinSeparation ( const SeparationScenario scenario,
const DistanceProxy proxyA,
const Transformation xfA,
const DistanceProxy proxyB,
const Transformation xfB 
)

Finds the minimum separation.

Returns
indexes of proxy A's and proxy B's vertices that have the minimum distance between them and what that distance is.

Referenced by playrho::ToiOutput::GetToiViaSat().

◆ GetAABB() [1/2]

AABB GetAABB ( const DynamicTree tree)
inlinenoexcept

Gets the AABB for the given dynamic tree.

Gets the AABB that encloses all other AABB instances that are within the given dynamic tree.

Returns
Enclosing AABB or the "unset" AABB.

◆ GetAABB() [2/2]

constexpr AABB GetAABB ( const DynamicTree::TreeNode node)
constexprnoexcept

Gets the AABB of the given dynamic tree node.

Precondition
node must be a used node. I.e. IsUnused(node) must be false.

◆ GetAcceleration() [1/2]

Acceleration GetAcceleration ( const Body body)
inlinenoexcept

Gets the given body's acceleration.

Parameters
bodyBody whose acceleration should be returned.
See also
SetAcceleration(Body& body, Acceleration value).
Examples
World.cpp, and WorldBody.cpp.

Referenced by playrho::d2::Body::operator==().

◆ GetAcceleration() [2/2]

Acceleration playrho::d2::GetAcceleration ( const World world,
BodyID  id 
)

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 playrho::d2::GetAnchorA ( const World world,
JointID  id 
)

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

Exceptions
std::out_of_rangeIf given an invalid joint identifier.
Examples
GearJoint.cpp, MotorJoint.cpp, PrismaticJoint.cpp, RevoluteJoint.cpp, RopeJoint.cpp, WeldJoint.cpp, and WheelJoint.cpp.

Referenced by playrho::d2::World::GetCurrentLengthA(), and playrho::d2::World::GetJointTranslation().

◆ GetAnchorB()

Length2 playrho::d2::GetAnchorB ( const World world,
JointID  id 
)

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

Exceptions
std::out_of_rangeIf given an invalid joint identifier.
Examples
GearJoint.cpp, MotorJoint.cpp, PrismaticJoint.cpp, RevoluteJoint.cpp, RopeJoint.cpp, TargetJoint.cpp, WeldJoint.cpp, and WheelJoint.cpp.

Referenced by playrho::d2::World::GetCurrentLengthB(), and playrho::d2::World::GetJointTranslation().

◆ GetAngle() [1/4]

◆ GetAngle() [2/4]

Angle playrho::d2::GetAngle ( const World world,
BodyID  id 
)

Gets the angle of the identified body.

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

◆ GetAngle() [3/4]

Angle playrho::d2::GetAngle ( const World world,
const RevoluteJointConf conf 
)

Gets the current angle of the given configuration in the given world.

Parameters
worldThe world the given joint configuration relates to.
confConfiguration of the joint to get the angle for.
Exceptions
std::out_of_rangeIf given an invalid body identifier in the joint configuration.

◆ GetAngle() [4/4]

Angle playrho::d2::GetAngle ( const World world,
JointID  id 
)

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

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetAngularAcceleration() [1/2]

AngularAcceleration GetAngularAcceleration ( const Body body)
inlinenoexcept

◆ GetAngularAcceleration() [2/2]

AngularAcceleration playrho::d2::GetAngularAcceleration ( const World world,
BodyID  id 
)

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() [1/2]

NonNegative< Frequency > GetAngularDamping ( const Body body)
inlinenoexcept

◆ GetAngularDamping() [2/2]

Frequency playrho::d2::GetAngularDamping ( const World world,
BodyID  id 
)

Gets the angular damping of the body.

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ GetAngularLowerLimit() [1/2]

Angle playrho::d2::GetAngularLowerLimit ( const Joint object)

Gets the lower joint limit.

Exceptions
std::invalid_argumentIf not supported for the given joint's type.
Examples
PrismaticJoint.cpp, and RevoluteJoint.cpp.

Referenced by playrho::d2::Joint::GetAngularLowerLimit(), and playrho::d2::World::GetAngularLowerLimit().

◆ GetAngularLowerLimit() [2/2]

Angle playrho::d2::GetAngularLowerLimit ( const World world,
JointID  id 
)

Get the lower joint limit.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetAngularMass() [1/2]

RotInertia playrho::d2::GetAngularMass ( const Joint object)

Gets the given joint's angular mass.

Exceptions
std::invalid_argumentIf not supported for the given joint's type.
Examples
FrictionJoint.cpp, MotorJoint.cpp, PrismaticJoint.cpp, RevoluteJoint.cpp, and WheelJoint.cpp.

Referenced by playrho::d2::Joint::GetAngularMass(), and playrho::d2::World::GetAngularMass().

◆ GetAngularMass() [2/2]

RotInertia playrho::d2::GetAngularMass ( const World world,
JointID  id 
)

Gets the computed angular rotational inertia used by the joint.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetAngularMotorImpulse() [1/2]

AngularMomentum playrho::d2::GetAngularMotorImpulse ( const Joint object)

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

Exceptions
std::invalid_argumentIf not supported for the given joint's type.
Examples
PrismaticJoint.cpp, and RevoluteJoint.cpp.

Referenced by playrho::d2::Joint::GetAngularMotorImpulse(), playrho::d2::World::GetAngularMotorImpulse(), playrho::d2::Joint::GetMotorTorque(), and playrho::d2::World::GetMotorTorque().

◆ GetAngularMotorImpulse() [2/2]

AngularMomentum playrho::d2::GetAngularMotorImpulse ( const World world,
JointID  id 
)

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() [1/2]

Angle playrho::d2::GetAngularOffset ( const Joint object)

Gets the angular offset property of the specified joint if its type has one.

Exceptions
std::invalid_argumentIf not supported for the given joint's type.
Examples
MotorJoint.cpp, and PrismaticJoint.cpp.

Referenced by playrho::d2::Joint::GetAngularOffset(), and playrho::d2::World::GetAngularOffset().

◆ GetAngularOffset() [2/2]

Angle playrho::d2::GetAngularOffset ( const World world,
JointID  id 
)

Gets the target angular offset.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetAngularReaction() [1/2]

AngularMomentum playrho::d2::GetAngularReaction ( const Joint object)

Get the angular reaction on body-B.

◆ GetAngularReaction() [2/2]

AngularMomentum playrho::d2::GetAngularReaction ( const World world,
JointID  id 
)

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

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetAngularUpperLimit() [1/2]

Angle playrho::d2::GetAngularUpperLimit ( const Joint object)

Gets the upper joint limit.

Exceptions
std::invalid_argumentIf not supported for the given joint's type.
Examples
PrismaticJoint.cpp, and RevoluteJoint.cpp.

Referenced by playrho::d2::Joint::GetAngularUpperLimit(), and playrho::d2::World::GetAngularUpperLimit().

◆ GetAngularUpperLimit() [2/2]

Angle playrho::d2::GetAngularUpperLimit ( const World world,
JointID  id 
)

Get the upper joint limit.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetAngularVelocity() [1/5]

AngularVelocity GetAngularVelocity ( const Body body)
inlinenoexcept

Gets the angular velocity.

Parameters
bodyBody to get the angular velocity for.
Returns
the angular velocity.
See also
GetVelocity(const Body& body).
Examples
RevoluteJoint.cpp, WheelJoint.cpp, World.cpp, and WorldBody.cpp.

Referenced by playrho::d2::World::GetAngularVelocity(), playrho::d2::Body::GetBodyConf(), playrho::d2::Body::SetVelocity(), and playrho::d2::World::SetVelocity().

◆ GetAngularVelocity() [2/5]

AngularVelocity GetAngularVelocity ( const World world,
BodyID  id 
)
inline

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() [3/5]

AngularVelocity playrho::d2::GetAngularVelocity ( const World world,
const RevoluteJointConf conf 
)

Gets the current angular velocity of the given configuration.

Parameters
worldThe world the given joint configuration relates to.
confConfiguration of the joint to get the angular velocity for.
Exceptions
std::out_of_rangeIf given an invalid body identifier in the joint configuration.

◆ GetAngularVelocity() [4/5]

AngularVelocity playrho::d2::GetAngularVelocity ( const World world,
const WheelJointConf conf 
)

Gets the angular velocity for the given configuration within the specified world.

Parameters
worldThe world the given joint configuration relates to.
confConfiguration of the joint to get the angular velocity for.
Exceptions
std::out_of_rangeIf given an invalid body identifier in the joint configuration.

◆ GetAngularVelocity() [5/5]

AngularVelocity playrho::d2::GetAngularVelocity ( const World world,
JointID  id 
)

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

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetAssociationCount()

ShapeCounter playrho::d2::GetAssociationCount ( const World world)

Gets the count of body-shape associations in the given world.

Parameters
worldThe world in which to get the shape association count for.
See also
GetUsedShapesCount.
Examples
World.cpp.

◆ GetAwakeCount()

BodyCounter playrho::d2::GetAwakeCount ( const World world)

Gets the count of awake bodies in the given world.

Parameters
worldThe world for which to get the awake count for.
See also
Awaken.
Examples
World.cpp.

◆ GetBodies() [1/2]

const BodyIDs & playrho::d2::GetBodies ( const AabbTreeWorld world)
inlinenoexcept

Gets a container of valid world body identifiers for this constant world.

Gets a container of identifiers of bodies currently existing within this world. These are the bodies that had been created from previous calls to the CreateBody(const Body&) function that haven't yet been destroyed.

Returns
Container of body identifiers that can be iterated over using begin and end functions or using ranged-based for-loops.
See also
CreateBody(const Body&).
Examples
World.cpp, and WorldBody.cpp.

Referenced by playrho::d2::World::Awaken(), playrho::d2::World::CalcGravitationalAcceleration(), playrho::d2::World::FindClosestBody(), playrho::d2::World::GetAssociationCount(), playrho::d2::World::GetAwakeCount(), playrho::d2::detail::WorldModel< T >::GetBodies_(), playrho::d2::World::GetBodyCount(), playrho::d2::World::GetUsedShapesCount(), and playrho::d2::World::SetAccelerations().

◆ GetBodies() [2/2]

std::vector< BodyID > playrho::d2::GetBodies ( const World world)
inline

Gets the valid world body identifiers container for this constant world.

Gets a container enumerating the identifiers of bodies currently existing within this world. These are the bodies that had been created from previous calls to CreateBody(World&, const Body&) that haven't yet been destroyed by a call to Destroy(World& world, BodyID) or to Clear(World&).

Parameters
worldThe world whose body identifiers are to be returned for.
Returns
Container of body identifiers.
See also
CreateBody(World&, const Body&), Destroy(World& world, BodyID), Clear(World&).

◆ GetBodiesForProxies() [1/2]

const BodyIDs & playrho::d2::GetBodiesForProxies ( const AabbTreeWorld world)
inlinenoexcept

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

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

See also
Step.
Examples
World.cpp, and WorldBody.cpp.

Referenced by playrho::d2::detail::WorldModel< T >::GetBodiesForProxies_().

◆ GetBodiesForProxies() [2/2]

std::vector< BodyID > playrho::d2::GetBodiesForProxies ( const World world)
inline

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

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

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

◆ GetBody() [1/2]

const Body & playrho::d2::GetBody ( const AabbTreeWorld world,
BodyID  id 
)

Gets the identified body.

Exceptions
std::out_of_rangeif given an invalid id.
See also
SetBody, GetBodyRange.
Examples
World.cpp.

Referenced by playrho::d2::World::ApplyAngularImpulse(), playrho::d2::World::ApplyForce(), playrho::d2::World::ApplyLinearImpulse(), playrho::d2::AabbTreeWorld::Attach(), playrho::d2::World::Attach(), playrho::d2::AabbTreeWorld::Detach(), playrho::d2::World::Detach(), playrho::d2::World::GetAcceleration(), playrho::d2::World::GetAnchorA(), playrho::d2::World::GetAnchorB(), playrho::d2::World::GetAngle(), playrho::d2::World::GetAngularAcceleration(), playrho::d2::World::GetAngularDamping(), playrho::d2::World::GetAngularVelocity(), playrho::d2::detail::WorldModel< T >::GetBody_(), playrho::d2::World::GetInvMass(), playrho::d2::World::GetInvRotInertia(), playrho::d2::World::GetJointTranslation(), playrho::d2::World::GetLinearAcceleration(), playrho::d2::World::GetLinearDamping(), playrho::d2::World::GetLocalCenter(), playrho::d2::AabbTreeWorld::GetShapes(), playrho::d2::World::GetTransformation(), playrho::d2::World::GetType(), playrho::d2::World::GetVelocity(), playrho::d2::World::GetWorldCenter(), playrho::d2::World::IsAccelerable(), playrho::d2::World::IsAwake(), IsDestroyed(), playrho::d2::World::IsEnabled(), playrho::d2::World::IsFixedRotation(), playrho::d2::World::IsImpenetrable(), playrho::d2::World::IsMassDataDirty(), playrho::d2::World::IsSleepingAllowed(), playrho::d2::World::IsSpeedable(), playrho::d2::World::SetAcceleration(), playrho::d2::World::SetAngle(), playrho::d2::World::SetAngularDamping(), playrho::d2::World::SetAwake(), playrho::d2::World::SetEnabled(), playrho::d2::World::SetFixedRotation(), playrho::d2::World::SetImpenetrable(), playrho::d2::World::SetLinearDamping(), playrho::d2::World::SetLocation(), playrho::d2::World::SetMassData(), playrho::d2::World::SetSleepingAllowed(), playrho::d2::World::SetTransformation(), playrho::d2::World::SetType(), playrho::d2::World::SetVelocity(), playrho::d2::World::UnsetAwake(), and playrho::d2::World::UnsetImpenetrable().

◆ GetBody() [2/2]

Body playrho::d2::GetBody ( const World world,
BodyID  id 
)
inline

Gets the state of the identified body.

Exceptions
std::out_of_rangeIf given an out of range body identifier.
See also
CreateBody(World&, const Body&, bool), SetBody(World&, BodyID, const Body&), GetBodyRange.

◆ GetBodyA() [1/2]

BodyID playrho::d2::GetBodyA ( const World world,
ContactID  id 
)

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 playrho::d2::GetBodyA ( const World world,
JointID  id 
)

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

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetBodyB() [1/2]

BodyID playrho::d2::GetBodyB ( const World world,
ContactID  id 
)

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 playrho::d2::GetBodyB ( const World world,
JointID  id 
)

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

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetBodyConf()

BodyConf playrho::d2::GetBodyConf ( const Body body)

Gets the body definition for the given body.

Parameters
bodyBody to get the BodyConf for.

◆ GetBodyCount()

BodyCounter playrho::d2::GetBodyCount ( const World world)
noexcept

Gets the body count in the given world.

Returns
0 or higher.
Examples
World.cpp, and WorldBody.cpp.

◆ GetBodyRange() [1/2]

BodyCounter playrho::d2::GetBodyRange ( const AabbTreeWorld world)
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.
Examples
World.cpp, and WorldBody.cpp.

Referenced by playrho::d2::detail::WorldModel< T >::GetBodyRange_().

◆ GetBodyRange() [2/2]

BodyCounter playrho::d2::GetBodyRange ( const World world)
inlinenoexcept

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.
Parameters
worldThe world whose body range is to be returned for.

◆ GetCentripetalForce()

Force2 playrho::d2::GetCentripetalForce ( const World world,
BodyID  id,
const Length2 axis 
)

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.
Examples
WorldBody.cpp.

◆ GetChild()

DistanceProxy playrho::d2::GetChild ( const Shape shape,
ChildCounter  index 
)

Gets the "child" for the given index.

Parameters
shapeShape to get "child" shape of.
indexIndex to a child element of the shape. Value must be less than the number of child primitives of the shape.
Warning
The shape must remain in scope while the proxy is in use!
Exceptions
InvalidArgumentif the given index is out of range.
See also
GetChildCount

◆ GetChildCount() [1/3]

constexpr ChildCounter playrho::d2::GetChildCount ( const EdgeShapeConf )
constexprnoexcept

Gets the "child" count for the given shape configuration.

Returns
1.

◆ GetChildCount() [2/3]

constexpr ChildCounter GetChildCount ( const PolygonShapeConf )
constexprnoexcept

Gets the "child" count for the given shape configuration.

Returns
1.

◆ GetChildCount() [3/3]

ChildCounter playrho::d2::GetChildCount ( const Shape shape)
noexcept

Gets the number of child primitives of the shape.

Returns
Non-negative count.

◆ GetChildIndexA()

ChildCounter playrho::d2::GetChildIndexA ( const World world,
ContactID  id 
)

Gets the child primitive index A for the identified contact.

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

Referenced by playrho::d2::World::ComputeIntersectingAABB(), playrho::d2::World::GetChildIndexA(), and playrho::Contact::GetWorldManifold().

◆ GetChildIndexB()

ChildCounter playrho::d2::GetChildIndexB ( const World world,
ContactID  id 
)

Gets the child primitive index B for the identified contact.

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

Referenced by playrho::d2::World::ComputeIntersectingAABB(), playrho::d2::World::GetChildIndexB(), and playrho::Contact::GetWorldManifold().

◆ GetCollideConnected() [1/2]

bool playrho::d2::GetCollideConnected ( const Joint object)
noexcept

Gets collide connected.

Note
Modifying the collide connect flag won't work correctly because the flag is only checked when fixture AABBs begin to overlap.
Examples
DistanceJoint.cpp, FrictionJoint.cpp, GearJoint.cpp, Joint.cpp, MotorJoint.cpp, PulleyJoint.cpp, RevoluteJoint.cpp, RopeJoint.cpp, TargetJoint.cpp, WeldJoint.cpp, WheelJoint.cpp, and World.cpp.

Referenced by playrho::d2::World::GetCollideConnected(), playrho::d2::detail::JointModel< T >::GetCollideConnected_(), and playrho::d2::JointConf::Set().

◆ GetCollideConnected() [2/2]

bool playrho::d2::GetCollideConnected ( const World world,
JointID  id 
)

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() [1/2]

◆ GetContact() [2/2]

Contact playrho::d2::GetContact ( const World world,
ContactID  id 
)
inline

Gets the identified contact.

Exceptions
std::out_of_rangeIf given an out of range contact identifier.
See also
GetContantRange.

◆ GetContactCount()

ContactCounter GetContactCount ( const World world)
inlinenoexcept

Gets the count of contacts in the given world.

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

◆ GetContactRange() [1/2]

ContactCounter playrho::d2::GetContactRange ( const AabbTreeWorld world)
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.
Examples
World.cpp, and WorldContact.cpp.

Referenced by playrho::d2::detail::WorldModel< T >::GetContactRange_(), and playrho::d2::World::MakeTouchingMap().

◆ GetContactRange() [2/2]

ContactCounter playrho::d2::GetContactRange ( const World world)
inlinenoexcept

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.

◆ GetContactRelVelocity()

LinearVelocity2 playrho::d2::GetContactRelVelocity ( const Velocity velA,
const Length2 relA,
const Velocity velB,
const Length2 relB 
)
noexcept

Gets the contact relative velocity.

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

◆ GetContacts() [1/4]

KeyedContactIDs playrho::d2::GetContacts ( const AabbTreeWorld world)
inline

Gets a container of valid world contact identifiers.

Warning
contacts are created and destroyed in the middle of a time step. Use ContactFunction to avoid missing contacts.
Returns
Container of keyed contact IDs of existing contacts.

◆ GetContacts() [2/4]

const BodyContactIDs & playrho::d2::GetContacts ( const AabbTreeWorld world,
BodyID  id 
)

Gets the contacts associated with the identified body.

Exceptions
std::out_of_rangeif given an invalid id.
Examples
World.cpp, WorldBody.cpp, and WorldContact.cpp.

Referenced by playrho::d2::World::GetContactCount(), playrho::d2::detail::WorldModel< T >::GetContacts_(), and playrho::d2::World::GetTouchingCount().

◆ GetContacts() [3/4]

std::vector< KeyedContactID > playrho::d2::GetContacts ( const World world)
inline

Gets the contacts identified within the given world.

Note
Further information for each element of the returned container is available from functions like GetContact or GetManifold.

◆ GetContacts() [4/4]

std::vector< std::tuple< ContactKey, ContactID > > playrho::d2::GetContacts ( const World world,
BodyID  id 
)
inline

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 ContactFunction.
Exceptions
std::out_of_rangeIf given an out of range body identifier.
See also
GetBodyRange.

◆ GetConvexHullAsVector()

std::vector< Length2 > playrho::d2::GetConvexHullAsVector ( Span< const Length2 vertices)

Gets the convex hull for the given collection of vertices as a vector.

Returns
Counter-clockwise vertices that "gift-wrap" the given vertices starting with lowest right-most vertex.
See also
FindLowestRightMostVertex.

Referenced by playrho::d2::ConvexHull::Get(), and playrho::d2::PolygonShapeConf::Set().

◆ GetCurrentLengthA()

Length playrho::d2::GetCurrentLengthA ( const World world,
JointID  id 
)

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

Exceptions
std::out_of_rangeIf given an invalid joint identifier.
Examples
PulleyJoint.cpp.

◆ GetCurrentLengthB()

Length playrho::d2::GetCurrentLengthB ( const World world,
JointID  id 
)

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

Exceptions
std::out_of_rangeIf given an invalid joint identifier.
Examples
PulleyJoint.cpp.

◆ GetDampingRatio() [1/2]

Real playrho::d2::GetDampingRatio ( const Joint object)

Gets the given joint's damping ratio property if it has one.

Exceptions
std::invalid_argumentIf not supported for the given joint's type.
Examples
DistanceJoint.cpp, PrismaticJoint.cpp, TargetJoint.cpp, WeldJoint.cpp, and WheelJoint.cpp.

Referenced by playrho::d2::Joint::GetDampingRatio(), and playrho::d2::World::GetDampingRatio().

◆ GetDampingRatio() [2/2]

Real playrho::d2::GetDampingRatio ( const World world,
JointID  id 
)

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.

◆ GetData()

const void* playrho::d2::GetData ( const Shape shape)
noexcept

Gets a pointer to the underlying data.

Note
Provided for introspective purposes like visitation.

◆ GetDefaultFriction()

Real playrho::d2::GetDefaultFriction ( const World world,
ContactID  id 
)

Gets the default friction amount for the identified contact.

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

Referenced by playrho::d2::World::GetDefaultFriction(), and playrho::d2::World::ResetFriction().

◆ GetDefaultRestitution()

Real playrho::d2::GetDefaultRestitution ( const World world,
ContactID  id 
)

Gets the default restitution amount for the identified contact.

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

Referenced by playrho::d2::World::GetDefaultRestitution(), and playrho::d2::World::ResetRestitution().

◆ GetDensity() [1/2]

NonNegative<AreaDensity> playrho::d2::GetDensity ( const Shape shape)
noexcept

◆ GetDensity() [2/2]

NonNegative< AreaDensity > playrho::d2::GetDensity ( const World world,
ShapeID  id 
)

Gets the density of this shape.

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

◆ GetDistanceJointConf() [1/2]

DistanceJointConf playrho::d2::GetDistanceJointConf ( const Joint joint)

Gets the definition data for the given joint.

Parameters
jointThe joint to get the configuration for.
Exceptions
std::bad_castIf the given joint's type is inappropriate for getting this value.
Examples
DistanceJoint.cpp, and World.cpp.

◆ GetDistanceJointConf() [2/2]

DistanceJointConf playrho::d2::GetDistanceJointConf ( const World world,
BodyID  bodyA,
BodyID  bodyB,
const Length2 anchorA = Length2{},
const Length2 anchorB = Length2{} 
)

Gets the configuration for a joint with the given parameters.

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ GetFilter()

Filter playrho::d2::GetFilter ( const Shape shape)
noexcept

Gets the filter value for the given shape.

Returns
Filter for the given shape or the default filter is the shape has no value.
See also
SetFilter(Shape& shape, Filter value);.
Examples
Shape.cpp.

Referenced by playrho::d2::detail::ShapeModel< T >::GetFilter_(), playrho::d2::World::GetFilterData(), playrho::d2::detail::SetFilter(), and playrho::d2::Shape::ShouldCollide().

◆ GetFilterData()

Filter playrho::d2::GetFilterData ( const World world,
ShapeID  id 
)

Gets the filter data for the identified shape.

Exceptions
std::out_of_rangeIf given an invalid identifier.
See also
SetFilterData.
Examples
World.cpp, and WorldShape.cpp.

◆ GetFixturesForProxies()

const BodyShapeIDs & playrho::d2::GetFixturesForProxies ( const AabbTreeWorld world)
inlinenoexcept

Gets the fixtures-for-proxies for this world.

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

See also
Step.

◆ GetFrequency() [1/2]

Frequency playrho::d2::GetFrequency ( const Joint object)

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

Exceptions
std::invalid_argumentIf not supported for the given joint's type.
Examples
DistanceJoint.cpp, PrismaticJoint.cpp, TargetJoint.cpp, WeldJoint.cpp, and WheelJoint.cpp.

Referenced by playrho::d2::Joint::GetFrequency(), and playrho::d2::World::GetFrequency().

◆ GetFrequency() [2/2]

Frequency playrho::d2::GetFrequency ( const World world,
JointID  id 
)

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

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetFriction() [1/3]

◆ GetFriction() [2/3]

NonNegativeFF< Real > playrho::d2::GetFriction ( const World world,
ContactID  id 
)

Gets the friction used with the identified contact.

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

◆ GetFriction() [3/3]

NonNegativeFF< Real > playrho::d2::GetFriction ( const World world,
ShapeID  id 
)

Gets the coefficient of friction of the specified shape.

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

◆ GetFrictionJointConf() [1/2]

FrictionJointConf playrho::d2::GetFrictionJointConf ( const Joint joint)

Gets the definition data for the given joint.

Exceptions
std::bad_castIf the given joint's type is inappropriate for getting this value.
Examples
FrictionJoint.cpp.

◆ GetFrictionJointConf() [2/2]

FrictionJointConf playrho::d2::GetFrictionJointConf ( const World world,
BodyID  bodyA,
BodyID  bodyB,
const Length2 anchor 
)

Gets the confguration for the given parameters.

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ GetFwdPerpendicular()

constexpr UnitVec playrho::d2::GetFwdPerpendicular ( const UnitVec vector)
constexprnoexcept

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

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

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

Referenced by CalcSearchDirection(), GetFwdNormalsArray(), GetFwdNormalsVector(), GetManifold(), GetSeparationScenario(), and playrho::d2::VelocityConstraint::GetTangent().

◆ GetGearJointConf() [1/2]

GearJointConf playrho::d2::GetGearJointConf ( const Joint joint)

Gets the definition data for the given joint.

Exceptions
std::bad_castIf the given joint's type is inappropriate for getting this value.
Examples
GearJoint.cpp, and World.cpp.

◆ GetGearJointConf() [2/2]

GearJointConf playrho::d2::GetGearJointConf ( const World world,
JointID  id1,
JointID  id2,
Real  ratio = Real{1} 
)

Gets the configuration for the given parameters.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetGroundAnchorA() [1/2]

Length2 playrho::d2::GetGroundAnchorA ( const Joint object)
Exceptions
std::invalid_argumentIf not supported for the given joint's type.
Examples
PrismaticJoint.cpp, and PulleyJoint.cpp.

Referenced by playrho::d2::World::GetCurrentLengthA(), playrho::d2::Joint::GetGroundAnchorA(), and playrho::d2::World::GetGroundAnchorA().

◆ GetGroundAnchorA() [2/2]

Length2 playrho::d2::GetGroundAnchorA ( const World world,
JointID  id 
)

Get the first ground anchor.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetGroundAnchorB() [1/2]

Length2 playrho::d2::GetGroundAnchorB ( const Joint object)
Exceptions
std::invalid_argumentIf not supported for the given joint's type.
Examples
PrismaticJoint.cpp, and PulleyJoint.cpp.

Referenced by playrho::d2::World::GetCurrentLengthB(), playrho::d2::Joint::GetGroundAnchorB(), and playrho::d2::World::GetGroundAnchorB().

◆ GetGroundAnchorB() [2/2]

Length2 playrho::d2::GetGroundAnchorB ( const World world,
JointID  id 
)

Get the second ground anchor.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetHeight()

DynamicTree::Height GetHeight ( const DynamicTree tree)
inlinenoexcept

Gets the height of the binary tree.

Returns
Height of the tree (as stored in the root node) or 0 if the root node is not valid.
Examples
World.cpp.

Referenced by playrho::d2::DynamicTree::DestroyLeaf(), and playrho::d2::DynamicTree::ShiftOrigin().

◆ GetInvDeltaTime() [1/2]

Frequency playrho::d2::GetInvDeltaTime ( const AabbTreeWorld world)
inlinenoexcept

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() function having a non-zero delta-time.

See also
Step.

Referenced by playrho::d2::detail::WorldModel< T >::GetInvDeltaTime_(), and playrho::d2::World::Step().

◆ GetInvDeltaTime() [2/2]

Frequency playrho::d2::GetInvDeltaTime ( const World world)
inlinenoexcept

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 function having a non-zero delta-time.

Parameters
worldThe world whose inverse delta time is to be returned for.
See also
Step.

◆ GetInvMass() [1/2]

NonNegativeFF< InvMass > GetInvMass ( const Body body)
inlinenoexcept

Gets the inverse total mass of the body.

This is the cached result of dividing 1 by the body's mass. Often floating division is much slower than multiplication. As such, it's likely faster to multiply values by this inverse value than to redivide them all the time by the mass.

Returns
Value of zero or more representing the body's inverse mass (in 1/kg).
See also
SetInvMassData.
Examples
Body.cpp, and World.cpp.

Referenced by playrho::d2::World::ApplyForce(), playrho::d2::World::ApplyForceToCenter(), playrho::d2::Body::GetBodyConf(), GetBodyConstraint(), playrho::d2::World::GetInvMass(), playrho::d2::World::GetMass(), playrho::d2::Body::operator==(), and playrho::d2::World::SetForce().

◆ GetInvMass() [2/2]

InvMass playrho::d2::GetInvMass ( const World world,
BodyID  id 
)

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() [1/2]

NonNegativeFF< InvRotInertia > GetInvRotInertia ( const Body body)
inlinenoexcept

Gets the inverse rotational inertia of the body.

This is the cached result of dividing 1 by the body's rotational inertia. Often floating division is much slower than multiplication. As such, it's likely faster to multiply values by this inverse value than to redivide them all the time by the rotational inertia.

Returns
Inverse rotational inertia (in 1/kg-m^2).
Examples
RevoluteJoint.cpp.

Referenced by playrho::d2::World::ApplyForce(), playrho::d2::World::ApplyTorque(), playrho::d2::Body::GetBodyConf(), GetBodyConstraint(), playrho::d2::World::GetInvRotInertia(), playrho::d2::World::GetRotInertia(), playrho::d2::Body::operator==(), playrho::d2::World::SetForce(), and playrho::d2::World::SetTorque().

◆ GetInvRotInertia() [2/2]

InvRotInertia playrho::d2::GetInvRotInertia ( const World world,
BodyID  id 
)

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() [1/2]

const Joint & playrho::d2::GetJoint ( const AabbTreeWorld world,
JointID  id 
)

Gets the identified joint.

Exceptions
std::out_of_rangeif given an invalid ID.
Examples
DistanceJoint.cpp, GearJoint.cpp, MotorJoint.cpp, PrismaticJoint.cpp, and RopeJoint.cpp.

Referenced by playrho::d2::World::EnableLimit(), playrho::d2::World::EnableMotor(), playrho::d2::World::GetAnchorA(), playrho::d2::World::GetAnchorB(), playrho::d2::World::GetAngle(), playrho::d2::World::GetAngularLowerLimit(), playrho::d2::World::GetAngularMass(), playrho::d2::World::GetAngularMotorImpulse(), playrho::d2::World::GetAngularOffset(), playrho::d2::World::GetAngularReaction(), playrho::d2::World::GetAngularUpperLimit(), playrho::d2::World::GetAngularVelocity(), playrho::d2::World::GetBodyA(), playrho::d2::World::GetBodyB(), playrho::d2::World::GetCollideConnected(), playrho::d2::World::GetDampingRatio(), playrho::d2::World::GetFrequency(), playrho::d2::World::GetGroundAnchorA(), playrho::d2::World::GetGroundAnchorB(), playrho::d2::detail::WorldModel< T >::GetJoint_(), playrho::d2::World::GetJointTranslation(), playrho::d2::World::GetLength(), playrho::d2::World::GetLimitState(), playrho::d2::World::GetLinearMotorImpulse(), playrho::d2::World::GetLinearOffset(), playrho::d2::World::GetLinearReaction(), playrho::d2::World::GetLocalAnchorA(), playrho::d2::World::GetLocalAnchorB(), playrho::d2::World::GetLocalXAxisA(), playrho::d2::World::GetLocalYAxisA(), playrho::d2::World::GetMaxMotorTorque(), playrho::d2::World::GetMotorSpeed(), playrho::d2::World::GetRatio(), playrho::d2::World::GetReferenceAngle(), playrho::d2::World::GetTarget(), playrho::d2::World::GetType(), IsDestroyed(), playrho::d2::World::IsLimitEnabled(), playrho::d2::World::IsMotorEnabled(), playrho::d2::World::SetAngularLimits(), playrho::d2::World::SetAngularOffset(), playrho::d2::World::SetAwake(), playrho::d2::World::SetFrequency(), playrho::d2::World::SetLinearOffset(), playrho::d2::World::SetMaxMotorTorque(), playrho::d2::World::SetMotorSpeed(), playrho::d2::World::SetTarget(), and playrho::d2::World::ShiftOrigin().

◆ GetJoint() [2/2]

Joint playrho::d2::GetJoint ( const World world,
JointID  id 
)
inline

Gets the value of the identified joint.

Exceptions
std::out_of_rangeIf given an out of range joint identifier.
See also
GetJointRange.

◆ GetJointCount()

JointCounter GetJointCount ( const World world)
inline

Gets the count of joints in the given world.

Returns
0 or higher.
Examples
World.cpp.

◆ GetJointRange() [1/2]

JointCounter playrho::d2::GetJointRange ( const AabbTreeWorld world)
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.
Examples
World.cpp.

Referenced by playrho::d2::detail::WorldModel< T >::GetJointRange_().

◆ GetJointRange() [2/2]

JointCounter playrho::d2::GetJointRange ( const World world)
inlinenoexcept

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/4]

const JointIDs & playrho::d2::GetJoints ( const AabbTreeWorld world)
inlinenoexcept

Gets the container of joint IDs of the given world.

Gets a container enumerating the joints currently existing within this world. These are the joints that had been created from previous calls to the CreateJoint(const Joint&) function that haven't yet been destroyed.

Returns
Container of joint IDs of existing joints.
See also
CreateJoint(const Joint&).

◆ GetJoints() [2/4]

const BodyJointIDs & playrho::d2::GetJoints ( const AabbTreeWorld world,
BodyID  id 
)
Exceptions
std::out_of_rangeif given an invalid id.
Examples
World.cpp, and WorldBody.cpp.

Referenced by playrho::d2::World::GetJointCount(), and playrho::d2::detail::WorldModel< T >::GetJoints_().

◆ GetJoints() [3/4]

std::vector< JointID > playrho::d2::GetJoints ( const World world)
inline

Gets the joints of the specified world.

Note
These are joints created by previous calls to CreateJoint(World&, const Joint&) that haven't yet been destroyed by a call to Destroy(World& world, JointID) or Clear(World&).
See also
CreateJoint(World&, const Joint&), Destroy(World& world, JointID), Clear(World&).

◆ GetJoints() [4/4]

std::vector< std::pair< BodyID, JointID > > playrho::d2::GetJoints ( const World world,
BodyID  id 
)
inline

Gets the container of valid joints attached to the identified body.

Exceptions
std::out_of_rangeIf given an out of range body identifier.
See also
CreateJoint, GetBodyRange.

◆ GetJointTranslation()

Length playrho::d2::GetJointTranslation ( const World world,
JointID  id 
)

Gets the current joint translation.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.
Examples
PrismaticJoint.cpp, and WheelJoint.cpp.

◆ GetLength() [1/2]

Length playrho::d2::GetLength ( const Joint object)

Gets the length property of the specified joint if its type has one.

Exceptions
std::invalid_argumentIf not supported for the given joint's type.

◆ GetLength() [2/2]

Length playrho::d2::GetLength ( const World world,
JointID  id 
)

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() [1/2]

LimitState playrho::d2::GetLimitState ( const Joint object)
Exceptions
std::invalid_argumentIf not supported for the given joint's type.
Examples
Joint.cpp, PrismaticJoint.cpp, RevoluteJoint.cpp, and RopeJoint.cpp.

Referenced by playrho::d2::Joint::GetLimitState(), and playrho::d2::World::GetLimitState().

◆ GetLimitState() [2/2]

LimitState playrho::d2::GetLimitState ( const World world,
JointID  id 
)

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() [1/2]

◆ GetLinearAcceleration() [2/2]

LinearAcceleration2 playrho::d2::GetLinearAcceleration ( const World world,
BodyID  id 
)

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() [1/2]

NonNegative< Frequency > GetLinearDamping ( const Body body)
inlinenoexcept

◆ GetLinearDamping() [2/2]

Frequency playrho::d2::GetLinearDamping ( const World world,
BodyID  id 
)

Gets the linear damping of the body.

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ GetLinearLowerLimit()

Length playrho::d2::GetLinearLowerLimit ( const Joint object)

Gets the lower linear joint limit.

Exceptions
std::invalid_argumentIf not supported for the given joint's type.
Examples
PrismaticJoint.cpp, and RevoluteJoint.cpp.

Referenced by playrho::d2::Joint::GetLinearLowerLimit().

◆ GetLinearMotorImpulse() [1/2]

Momentum playrho::d2::GetLinearMotorImpulse ( const Joint object)
Exceptions
std::invalid_argumentIf not supported for the given joint's type.
Examples
PrismaticJoint.cpp, and RevoluteJoint.cpp.

Referenced by playrho::d2::Joint::GetLinearMotorImpulse(), playrho::d2::World::GetLinearMotorImpulse(), and playrho::d2::World::GetMotorForce().

◆ GetLinearMotorImpulse() [2/2]

Momentum playrho::d2::GetLinearMotorImpulse ( const World world,
JointID  id 
)

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

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetLinearOffset() [1/2]

Length2 playrho::d2::GetLinearOffset ( const Joint object)

Gets the linear offset property of the specified joint if its type has one.

Exceptions
std::invalid_argumentIf not supported for the given joint's type.
Examples
MotorJoint.cpp, and PrismaticJoint.cpp.

Referenced by playrho::d2::Joint::GetLinearOffset(), and playrho::d2::World::GetLinearOffset().

◆ GetLinearOffset() [2/2]

Length2 playrho::d2::GetLinearOffset ( const World world,
JointID  id 
)

Gets the target linear offset, in frame A.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetLinearReaction() [1/2]

Momentum2 playrho::d2::GetLinearReaction ( const Joint object)

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

◆ GetLinearReaction() [2/2]

Momentum2 playrho::d2::GetLinearReaction ( const World world,
JointID  id 
)

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

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetLinearUpperLimit()

Length playrho::d2::GetLinearUpperLimit ( const Joint object)

Gets the upper linear joint limit.

Exceptions
std::invalid_argumentIf not supported for the given joint's type.
Examples
PrismaticJoint.cpp, and RevoluteJoint.cpp.

Referenced by playrho::d2::Joint::GetLinearUpperLimit().

◆ GetLinearVelocity() [1/3]

LinearVelocity2 GetLinearVelocity ( const Body body)
inlinenoexcept

Gets the linear velocity of the center of mass.

Parameters
bodyBody to get the linear velocity for.
Returns
the linear velocity of the center of mass.
See also
GetVelocity(const Body& body).
Examples
PrismaticJoint.cpp, World.cpp, and WorldBody.cpp.

Referenced by playrho::d2::Body::GetBodyConf(), playrho::d2::World::GetCentripetalForce(), playrho::d2::Body::SetVelocity(), and playrho::d2::World::SetVelocity().

◆ GetLinearVelocity() [2/3]

LinearVelocity2 GetLinearVelocity ( const World world,
BodyID  id 
)
inline

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.

◆ GetLinearVelocity() [3/3]

LinearVelocity playrho::d2::GetLinearVelocity ( const World world,
const PrismaticJointConf joint 
)
noexcept

Gets the current linear velocity of the given configuration.

Exceptions
std::out_of_rangeIf given an invalid body identifier in the given joint conifguration.

◆ GetLinearVelocityFromLocalPoint()

LinearVelocity2 GetLinearVelocityFromLocalPoint ( const Body body,
const Length2 localPoint 
)
inlinenoexcept

Gets the linear velocity from a local point.

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

◆ GetLinearVelocityFromWorldPoint()

LinearVelocity2 GetLinearVelocityFromWorldPoint ( const Body body,
const Length2 worldPoint 
)
inlinenoexcept

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

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

Referenced by playrho::d2::Body::GetLinearVelocityFromLocalPoint().

◆ GetLocalAnchorA() [1/2]

Length2 playrho::d2::GetLocalAnchorA ( const Joint object)

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

◆ GetLocalAnchorA() [2/2]

Length2 playrho::d2::GetLocalAnchorA ( const World world,
JointID  id 
)

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

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetLocalAnchorB() [1/2]

Length2 playrho::d2::GetLocalAnchorB ( const Joint object)

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

◆ GetLocalAnchorB() [2/2]

Length2 playrho::d2::GetLocalAnchorB ( const World world,
JointID  id 
)

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

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetLocalCenter()

Length2 playrho::d2::GetLocalCenter ( const World world,
BodyID  id 
)

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

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ GetLocalPoint() [1/2]

Length2 GetLocalPoint ( const Body body,
const Length2 worldPoint 
)
inlinenoexcept

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

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

Referenced by playrho::d2::World::GetDistanceJointConf(), playrho::d2::World::GetFrictionJointConf(), playrho::d2::World::GetMotorJointConf(), playrho::d2::World::GetPrismaticJointConf(), playrho::d2::World::GetPulleyJointConf(), playrho::d2::World::GetRevoluteJointConf(), playrho::d2::World::GetWeldJointConf(), and playrho::d2::World::GetWheelJointConf().

◆ GetLocalPoint() [2/2]

Length2 GetLocalPoint ( const World world,
BodyID  id,
const Length2 worldPoint 
)
inline

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

Parameters
worldThe world in which the identified body exists.
idIdentifier 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() [1/2]

RotInertia GetLocalRotInertia ( const Body body)
inlinenoexcept

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

Returns
the rotational inertia.
See also
Body::GetInvRotInertia, Body::SetInvMassData.

Referenced by playrho::d2::World::GetMassData().

◆ GetLocalRotInertia() [2/2]

RotInertia GetLocalRotInertia ( const World world,
BodyID  id 
)
inline

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() [1/2]

UnitVec GetLocalVector ( const Body body,
const UnitVec uv 
)
inlinenoexcept

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

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

Referenced by playrho::d2::World::GetPrismaticJointConf(), and playrho::d2::World::GetWheelJointConf().

◆ GetLocalVector() [2/2]

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

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

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ GetLocalXAxisA() [1/2]

UnitVec playrho::d2::GetLocalXAxisA ( const Joint object)

Gets the given joint's local X axis A if its type supports that.

Exceptions
std::invalid_argumentIf not supported for the given joint's type.
Examples
PrismaticJoint.cpp, RevoluteJoint.cpp, and WheelJoint.cpp.

Referenced by playrho::d2::World::GetGearJointConf(), playrho::d2::World::GetJointTranslation(), playrho::d2::World::GetLinearVelocity(), playrho::d2::Joint::GetLocalXAxisA(), and playrho::d2::World::GetLocalXAxisA().

◆ GetLocalXAxisA() [2/2]

UnitVec playrho::d2::GetLocalXAxisA ( const World world,
JointID  id 
)

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() [1/2]

UnitVec playrho::d2::GetLocalYAxisA ( const Joint object)

Gets the given joint's local Y axis A if its type supports that.

Exceptions
std::invalid_argumentIf not supported for the given joint's type.
Examples
PrismaticJoint.cpp, RevoluteJoint.cpp, and WheelJoint.cpp.

Referenced by playrho::d2::Joint::GetLocalYAxisA(), and playrho::d2::World::GetLocalYAxisA().

◆ GetLocalYAxisA() [2/2]

UnitVec playrho::d2::GetLocalYAxisA ( const World world,
JointID  id 
)

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() [1/2]

Length2 GetLocation ( const Body body)
inlinenoexcept

Gets the body's origin location.

This is the location of the body's origin relative to its world. The location of the body after stepping the world's physics simulations is dependent on a number of factors:

  1. Location at the last time step.
  2. Forces acting on the body (gravity, applied force, applied impulse).
  3. The mass data of the body.
  4. Damping of the body.
  5. Restitution and friction values of the body's shape parts when they experience collisions.
    Returns
    World location of the body's origin.
    See also
    GetAngle.
Examples
DistanceJoint.cpp, FrictionJoint.cpp, GearJoint.cpp, HelloWorld.cpp, MotorJoint.cpp, PrismaticJoint.cpp, RevoluteJoint.cpp, RopeJoint.cpp, WeldJoint.cpp, WheelJoint.cpp, World.cpp, and WorldBody.cpp.

Referenced by playrho::d2::World::CalcGravitationalAcceleration(), playrho::d2::World::FindClosestBody(), playrho::d2::World::GetCentripetalForce(), playrho::d2::Body::GetLocation(), playrho::d2::World::GetMotorJointConf(), playrho::d2::Body::GetPosition(), GetPosition(), and playrho::d2::World::SetMassData().

◆ GetLocation() [2/2]

Length2 GetLocation ( const World world,
BodyID  id 
)
inline

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() [1/4]

Manifold playrho::d2::GetManifold ( bool  flipped,
const DistanceProxy shape0,
const Transformation xf0,
VertexCounter  idx0,
const DistanceProxy shape1,
const Transformation xf1,
VertexCounter2  indices1,
const Manifold::Conf conf 
)

Gets a face-to-face based manifold.

Parameters
flippedWhether to flip the resulting manifold (between face-A and face-B).
shape0Shape 0. This should be shape A for face-A type manifold or shape B for face-B type manifold. Must have a vertex count of more than one.
xf0Transform 0. This should be transform A for face-A type manifold or transform B for face-B type manifold.
idx0Index 0. This should be the index of the vertex and normal of shape0 that had the maximal separation distance from any vertex in shape1.
shape1Shape 1. This should be shape B for face-A type manifold or shape A for face-B type manifold. Must have a vertex count of more than one.
xf1Transform 1. This should be transform B for face-A type manifold or transform A for face-B type manifold.
indices1Index 1. This is the first and possibly second index of the vertex of shape1 that had the maximal separation distance from the edge of shape0 identified by idx0.
confManifold configuration data.

< Face offset.

< Face offset.

◆ GetManifold() [2/4]

Manifold playrho::d2::GetManifold ( bool  flipped,
Length  totalRadius,
const DistanceProxy shape,
const Transformation sxf,
const Length2 point,
const Transformation xfm 
)

Computes manifolds for face-to-point collision.

Precondition
The given distance proxy GetVertexCount() must be one or greater.

< Center of circle in frame of polygon.

< Center of circle in frame of polygon.

◆ GetManifold() [3/4]

const Manifold & playrho::d2::GetManifold ( const AabbTreeWorld world,
ContactID  id 
)

Gets the identified manifold.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.
See also
SetManifold, GetContactRange.
Examples
World.cpp.

Referenced by playrho::d2::Manifold::CollideShapes(), playrho::d2::detail::WorldModel< T >::GetManifold_(), playrho::d2::World::GetWorldManifold(), and playrho::d2::World::SameTouching().

◆ GetManifold() [4/4]

Manifold playrho::d2::GetManifold ( const World world,
ContactID  id 
)
inline

Gets the manifold for the identified contact.

Note
There is a manifold for every contact and vice-versa.
Exceptions
std::out_of_rangeIf given an out of range contact identifier.
See also
SetManifold, GetContantRange.

◆ GetMass() [1/2]

Mass GetMass ( const Body body)
inlinenoexcept

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.
See also
GetInvMass, SetInvMassData
Examples
World.cpp, and WorldBody.cpp.

Referenced by playrho::d2::World::CalcGravitationalAcceleration(), playrho::d2::World::GetCentripetalForce(), playrho::d2::Body::GetForce(), playrho::d2::Body::GetLocalRotInertia(), playrho::d2::World::GetLocalRotInertia(), and playrho::d2::World::GetMassData().

◆ GetMass() [2/2]

Mass GetMass ( const World world,
BodyID  id 
)
inline

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/6]

MassData playrho::d2::GetMassData ( const MultiShapeConf arg)

Gets the mass data for the given shape configuration.

Computes the mass properties of this shape using its dimensions and density. The inertia tensor is computed about the local origin.

Returns
Mass data for this shape.

◆ GetMassData() [2/6]

MassData playrho::d2::GetMassData ( const Shape shape)

Gets the mass properties of this shape using its dimensions and density.

Returns
Mass data for this shape.

◆ GetMassData() [3/6]

MassData GetMassData ( const World world,
BodyID  id 
)
inline

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() [4/6]

MassData playrho::d2::GetMassData ( const World world,
ShapeID  id 
)

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

Exceptions
std::out_of_rangeIf given an invalid identifier.

◆ GetMassData() [5/6]

MassData playrho::d2::GetMassData ( Length  r,
NonNegative< AreaDensity density,
const Length2 location 
)

Computes the mass data for a circular shape.

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

◆ GetMassData() [6/6]

MassData playrho::d2::GetMassData ( Length  r,
NonNegative< AreaDensity density,
const Length2 v0,
const Length2 v1 
)

Computes the mass data for a linear shape.

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

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

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

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

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

◆ GetMaxForce()

Force playrho::d2::GetMaxForce ( const Joint object)

Gets the given joint's max force if its type supports that.

Exceptions
std::invalid_argumentIf not supported for the given joint's type.

◆ GetMaxImbalance()

DynamicTree::Height playrho::d2::GetMaxImbalance ( const DynamicTree tree)
noexcept

Gets the maximum imbalance.

This gets the maximum imbalance of nodes in the given tree.

Note
The imbalance is the difference in height of the two children of a node.
Examples
World.cpp.

◆ GetMaxMotorForce()

Force playrho::d2::GetMaxMotorForce ( const Joint object)

Gets the given joint's max motor force if its type supports that.

Exceptions
std::invalid_argumentIf not supported for the given joint's type.
Examples
PrismaticJoint.cpp, and RevoluteJoint.cpp.

Referenced by playrho::d2::Joint::GetMaxMotorForce().

◆ GetMaxMotorTorque() [1/2]

Torque playrho::d2::GetMaxMotorTorque ( const Joint object)

Gets the given joint's max motor torque if its type supports that.

Exceptions
std::invalid_argumentIf not supported for the given joint's type.
Examples
PrismaticJoint.cpp, RevoluteJoint.cpp, and WheelJoint.cpp.

Referenced by playrho::d2::Joint::GetMaxMotorTorque(), and playrho::d2::World::GetMaxMotorTorque().

◆ GetMaxMotorTorque() [2/2]

Torque playrho::d2::GetMaxMotorTorque ( const World world,
JointID  id 
)

Gets the max motor torque.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetMaxSeparation() [1/3]

SeparationInfo playrho::d2::GetMaxSeparation ( const DistanceProxy proxy1,
const DistanceProxy proxy2,
Length  stop = MaxFloat * Meter 
)

Gets the max separation information.

Returns
Index of the vertex and normal from proxy1, index of the vertex from proxy2 (that had the maximum separation distance from each other in the direction of that normal), and the maximal distance.
See also
Distance.

◆ GetMaxSeparation() [2/3]

SeparationInfo playrho::d2::GetMaxSeparation ( const DistanceProxy proxy1,
const Transformation xf1,
const DistanceProxy proxy2,
const Transformation xf2 
)

Gets the max separation information.

Note
Prefer using this function - over the GetMaxSeparation function that takes a stopping length - when it's already known that the two convex shapes' AABBs overlap.
Returns
Index of the vertex and normal from proxy1, index of the vertex from proxy2 (that had the maximum separation distance from each other in the direction of that normal), and the maximal distance.
See also
Distance.

◆ GetMaxSeparation() [3/3]

SeparationInfo playrho::d2::GetMaxSeparation ( const DistanceProxy proxy1,
const Transformation xf1,
const DistanceProxy proxy2,
const Transformation xf2,
Length  stop 
)

Gets the max separation information.

Returns
Index of the vertex and normal from proxy1, index of the vertex from proxy2 (that had the maximum separation distance from each other in the direction of that normal), and the maximal distance.
See also
Distance.

◆ GetMaxSeparation4x4()

SeparationInfo playrho::d2::GetMaxSeparation4x4 ( const DistanceProxy proxy1,
const Transformation xf1,
const DistanceProxy proxy2,
const Transformation xf2 
)

Gets the max separation information for the first four vertices of the two given shapes.

This is a version of the get-max-separation functions that is optimized for two quadrilateral (4-sided) polygons.

Returns
Index of the vertex and normal from proxy1, index of the vertex from proxy2 (that had the maximum separation distance from each other in the direction of that normal), and the maximal distance.
See also
Distance.

◆ GetMaxTorque()

Torque playrho::d2::GetMaxTorque ( const Joint object)

Gets the given joint's max torque if its type supports that.

Exceptions
std::invalid_argumentIf not supported for the given joint's type.

◆ GetMotorForce()

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

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

Exceptions
std::out_of_rangeIf given an invalid joint identifier.
Examples
PrismaticJoint.cpp.

◆ GetMotorJointConf() [1/2]

MotorJointConf playrho::d2::GetMotorJointConf ( const Joint joint)

Gets the definition data for the given joint.

Exceptions
std::bad_castIf the given joint's type is inappropriate for getting this value.
Examples
MotorJoint.cpp, and World.cpp.

◆ GetMotorJointConf() [2/2]

MotorJointConf playrho::d2::GetMotorJointConf ( const World world,
BodyID  bA,
BodyID  bB 
)

Gets the confguration for the given parameters.

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ GetMotorSpeed() [1/2]

AngularVelocity playrho::d2::GetMotorSpeed ( const Joint object)

Gets the given joint's motor speed if its type supports that.

Exceptions
std::invalid_argumentIf not supported for the given joint's type.
Examples
DistanceJoint.cpp, FrictionJoint.cpp, PrismaticJoint.cpp, RevoluteJoint.cpp, and WheelJoint.cpp.

Referenced by playrho::d2::Joint::GetMotorSpeed(), and playrho::d2::World::GetMotorSpeed().

◆ GetMotorSpeed() [2/2]

AngularVelocity playrho::d2::GetMotorSpeed ( const World world,
JointID  id 
)

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() [1/2]

Torque GetMotorTorque ( const Joint joint,
Frequency  inv_dt 
)
inline

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

Exceptions
std::invalid_argumentIf not supported for the given joint's type.
Examples
RevoluteJoint.cpp, and WheelJoint.cpp.

◆ GetMotorTorque() [2/2]

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

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

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetName()

const char * playrho::d2::GetName ( Manifold::Type  type)
noexcept

Gets a unique name for the given manifold type.

Parameters
typeManifold type to get name for. Must be one of the enumerated values.
Examples
DistanceJoint.cpp, FrictionJoint.cpp, GearJoint.cpp, MotorJoint.cpp, PrismaticJoint.cpp, PulleyJoint.cpp, RevoluteJoint.cpp, RopeJoint.cpp, TargetJoint.cpp, WeldJoint.cpp, and WheelJoint.cpp.

◆ GetNext()

constexpr DynamicTree::Size GetNext ( const DynamicTree::TreeNode node)
constexprnoexcept

Gets the next index of the given node.

Precondition
The given node is unused, i.e.: IsUnused(node) is true.

◆ GetNormal()

UnitVec playrho::d2::GetNormal ( const VelocityConstraint vc)
inlinenoexcept

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

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

◆ GetNormalized() [1/2]

Position playrho::d2::GetNormalized ( const Position val)
inlinenoexcept

Gets the "normalized" position.

Enforces a wrap-around of one rotation on the angular position.

Note
Use to prevent unbounded angles in positions.
Examples
World.cpp.

Referenced by playrho::d2::World::GetGearJointConf().

◆ GetNormalized() [2/2]

Sweep GetNormalized ( Sweep  sweep)
inlinenoexcept

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

Parameters
sweepSweep to return with its angles normalized.
Returns
Sweep with its position 0 angle to be between -2 pi and 2 pi and its position 1 angle reduced by the amount the position 0 angle was reduced by.

◆ GetPerimeter()

constexpr Length playrho::d2::GetPerimeter ( const AABB aabb)
constexprnoexcept

Gets the perimeter length of the 2-dimensional AABB.

Precondition
The sizes of each of the AABB's ranges are representable.
Returns
Twice the sum of the width and height.
See also
https://en.wikipedia.org/wiki/Perimeter

Referenced by ComputePerimeterRatio(), ComputeTotalPerimeter(), and playrho::d2::DynamicTree::RebuildBottomUp().

◆ GetPointDelta()

constexpr Length2 playrho::d2::GetPointDelta ( const SimplexEdge sv)
constexprnoexcept

Gets "w".

Returns
2-dimensional vector value of the simplex edge's point B minus its point A.

Referenced by playrho::d2::Simplex::CalcMetric(), CalcSearchDirection(), playrho::d2::Simplex::Get(), and GetScaledDelta().

◆ GetPointStates()

PointStates playrho::d2::GetPointStates ( const Manifold manifold1,
const Manifold manifold2 
)
noexcept

Computes the before and after like point states given two manifolds.

Note
This can be useful for analyzing collision responses like in the world's pre-solve contact event listener.
Examples
World.cpp.

◆ GetPosition()

Position playrho::d2::GetPosition ( const Position pos0,
const Position pos1,
Real  beta 
)
noexcept

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

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

◆ GetPrismaticJointConf() [1/2]

PrismaticJointConf playrho::d2::GetPrismaticJointConf ( const Joint joint)

Gets the definition data for the given joint.

Exceptions
std::bad_castIf the given joint's type is inappropriate for getting this value.
Examples
GearJoint.cpp, PrismaticJoint.cpp, and World.cpp.

◆ GetPrismaticJointConf() [2/2]

PrismaticJointConf playrho::d2::GetPrismaticJointConf ( const World world,
BodyID  bA,
BodyID  bB,
const Length2 anchor,
const UnitVec axis 
)

Gets the configuration for the given parameters.

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ GetProxies()

const std::vector< DynamicTree::Size > & playrho::d2::GetProxies ( const AabbTreeWorld world,
BodyID  id 
)

Gets the proxies for the identified body.

Exceptions
std::out_of_rangeIf given an invalid identifier.

◆ GetPSM()

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

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

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

◆ GetPulleyJointConf() [1/2]

PulleyJointConf playrho::d2::GetPulleyJointConf ( const Joint joint)

Gets the definition data for the given joint.

Exceptions
std::bad_castIf the given joint's type is inappropriate for getting this value.
Examples
PulleyJoint.cpp, and World.cpp.

◆ GetPulleyJointConf() [2/2]

PulleyJointConf playrho::d2::GetPulleyJointConf ( const World world,
BodyID  bA,
BodyID  bB,
const Length2 groundA,
const Length2 groundB,
const Length2 anchorA,
const Length2 anchorB 
)

Gets the configuration for the given parameters.

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ GetRatio() [1/2]

Real playrho::d2::GetRatio ( const Joint object)

Gets the given joint's ratio property if it has one.

Exceptions
std::invalid_argumentIf not supported for the given joint's type.

◆ GetRatio() [2/2]

Real playrho::d2::GetRatio ( const World world,
JointID  id 
)

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

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetReferenceAngle() [1/2]

Angle playrho::d2::GetReferenceAngle ( const Joint object)

◆ GetReferenceAngle() [2/2]

Angle playrho::d2::GetReferenceAngle ( const World world,
JointID  id 
)

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

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetReflectionMatrix()

constexpr auto playrho::d2::GetReflectionMatrix ( const UnitVec axis)
constexpr

Gets the reflection matrix for the given unit vector that defines the normal of the line through the origin that points should be reflected against.

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

◆ GetResourceStats()

std::optional< pmr::StatsResource::Stats > playrho::d2::GetResourceStats ( const World world)
inlinenoexcept

Gets the polymorphic memory resource allocator statistics of the specified world.

Note
This will be the empty value unless the world configuration the given world was constructed with specified the collection of these statistics.
This information can be used to tweak the world configuration to pre-allocate enough space to avoid the less deterministic performance behavior of dynamic memory allocation during world step processing that may otherwise occur.
Parameters
worldThe world to get the memory resource allocator statistics for.
See also
WorldConf.

◆ GetRestitution() [1/3]

Real playrho::d2::GetRestitution ( const Shape shape)
noexcept

◆ GetRestitution() [2/3]

Real playrho::d2::GetRestitution ( const World world,
ContactID  id 
)

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() [3/3]

Real playrho::d2::GetRestitution ( const World world,
ShapeID  id 
)

Gets the coefficient of restitution of the specified shape.

Exceptions
std::out_of_rangeIf given an invalid identifier.

◆ GetRevoluteJointConf() [1/2]

RevoluteJointConf playrho::d2::GetRevoluteJointConf ( const Joint joint)

Gets the definition data for the given joint.

Exceptions
std::bad_castIf the given joint's type is inappropriate for getting this value.
Examples
GearJoint.cpp, and RevoluteJoint.cpp.

◆ GetRevoluteJointConf() [2/2]

RevoluteJointConf playrho::d2::GetRevoluteJointConf ( const World world,
BodyID  bodyA,
BodyID  bodyB,
const Length2 anchor 
)

Gets the configuration for the given parameters.

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ GetRevPerpendicular()

constexpr UnitVec playrho::d2::GetRevPerpendicular ( const UnitVec vector)
constexprnoexcept

◆ GetRopeJointConf()

RopeJointConf playrho::d2::GetRopeJointConf ( const Joint joint)

Gets the definition data for the given joint.

Exceptions
std::bad_castIf the given joint's type is inappropriate for getting this value.
Examples
RopeJoint.cpp.

◆ GetRotInertia() [1/2]

RotInertia GetRotInertia ( const Body body)
inlinenoexcept

Gets the rotational inertia of the body.

Parameters
bodyBody to get the rotational inertia for.
Returns
the rotational inertia.
See also
Body::GetInvRotInertia, Body::SetInvMassData.
Examples
WorldBody.cpp.

Referenced by playrho::d2::Body::GetLocalRotInertia(), playrho::d2::World::GetLocalRotInertia(), and playrho::d2::Body::GetTorque().

◆ GetRotInertia() [2/2]

RotInertia GetRotInertia ( const World world,
BodyID  id 
)
inline

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.

◆ GetSeparationScenario()

SeparationScenario playrho::d2::GetSeparationScenario ( IndexPair3  indices,
const DistanceProxy proxyA,
const Transformation xfA,
const DistanceProxy proxyB,
const Transformation xfB 
)

Gets a separation finder for the given inputs.

Parameters
indicesCollection of 1 to 3 index pairs. A points-type finder will be returned if given 1 index pair. A face-type finder will be returned otherwise.
proxyAProxy A.
xfATransformation A.
proxyBProxy B.
xfBTransformation B.
Precondition
empty(indices) is false.
proxyA and proxyB both have more than zero vertices.

Referenced by playrho::ToiOutput::GetToiViaSat().

◆ GetShape() [1/2]

◆ GetShape() [2/2]

Shape playrho::d2::GetShape ( const World world,
ShapeID  id 
)
inline

Gets the shape associated with the identifier.

Exceptions
std::out_of_rangeIf given an out of range identifier.
See also
GetShapeRange.

◆ GetShapeA()

ShapeID playrho::d2::GetShapeA ( const World world,
ContactID  id 
)

Gets shape A of the identified contact.

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

Referenced by playrho::d2::World::ComputeIntersectingAABB(), playrho::d2::World::GetDefaultFriction(), playrho::d2::World::GetDefaultRestitution(), playrho::d2::World::GetShapeA(), and playrho::Contact::GetWorldManifold().

◆ GetShapeB()

ShapeID playrho::d2::GetShapeB ( const World world,
ContactID  id 
)

Gets shape B of the identified contact.

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

Referenced by playrho::d2::World::ComputeIntersectingAABB(), playrho::d2::World::GetDefaultFriction(), playrho::d2::World::GetDefaultRestitution(), playrho::d2::World::GetShapeB(), and playrho::Contact::GetWorldManifold().

◆ GetShapeCount()

ShapeCounter playrho::d2::GetShapeCount ( const World world,
BodyID  id 
)

Gets the count of shapes associated with the identified body.

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

◆ GetShapeRange() [1/2]

ShapeCounter playrho::d2::GetShapeRange ( const AabbTreeWorld world)
noexcept

Gets the extent of the currently valid shape range.

Note
This is one higher than the maxium ShapeID that is in range for shape related functions.
Examples
World.cpp, and WorldShape.cpp.

Referenced by playrho::d2::detail::WorldModel< T >::GetShapeRange_().

◆ GetShapeRange() [2/2]

ShapeCounter playrho::d2::GetShapeRange ( const World world)
inlinenoexcept

Gets the extent of the currently valid shape range.

Note
This is one higher than the maxium ShapeID that is in range for shape related functions.

◆ GetShapes() [1/2]

const std::vector< ShapeID > & playrho::d2::GetShapes ( const AabbTreeWorld world,
BodyID  id 
)

◆ GetShapes() [2/2]

std::vector< ShapeID > playrho::d2::GetShapes ( const World world,
BodyID  id 
)
inline

Gets the identities of the shapes associated with the identified body.

Exceptions
std::out_of_rangeIf given an out of range body identifier.
See also
GetBodyRange, CreateBody, SetBody.

◆ GetSoonestContact()

ContactID playrho::d2::GetSoonestContact ( const Span< const KeyedContactID > &  ids,
const Span< const Contact > &  contacts 
)
noexcept

Gets the identifier of the contact with the lowest time of impact.

This finds the contact with the lowest (soonest) time of impact that's under one and returns its identifier.

Returns
Identifier of contact with the least time of impact under 1, or invalid contact ID.

◆ GetSubStepping() [1/2]

bool playrho::d2::GetSubStepping ( const AabbTreeWorld world)
inlinenoexcept

Gets whether or not sub-stepping is enabled.

See also
SetSubStepping, IsStepComplete.
Examples
World.cpp.

Referenced by playrho::d2::detail::WorldModel< T >::GetSubStepping_().

◆ GetSubStepping() [2/2]

bool playrho::d2::GetSubStepping ( const World world)
inlinenoexcept

Gets whether or not sub-stepping is enabled.

Parameters
worldThe world to return whether sub-stepping is enabled for.
See also
SetSubStepping, IsStepComplete.

◆ GetSupportIndex()

template<class T >
VertexCounter GetSupportIndex ( const DistanceProxy proxy,
dir 
)
inlinenoexcept

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

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

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

Referenced by playrho::d2::DistanceProxy::Distance().

◆ GetSweep()

◆ GetTangentSpeed()

LinearVelocity playrho::d2::GetTangentSpeed ( const World world,
ContactID  id 
)

Gets the tangent speed of the identified contact.

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

Referenced by playrho::d2::World::GetTangentSpeed().

◆ GetTarget() [1/2]

Length2 playrho::d2::GetTarget ( const Joint object)

Gets the given joint's target property if it has one.

Exceptions
std::invalid_argumentIf not supported for the given joint's type.
Examples
PrismaticJoint.cpp, TargetJoint.cpp, and World.cpp.

Referenced by playrho::d2::Joint::GetTarget(), and playrho::d2::World::GetTarget().

◆ GetTarget() [2/2]

Length2 playrho::d2::GetTarget ( const World world,
JointID  id 
)

Gets the target point.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetTargetJointConf()

TargetJointConf playrho::d2::GetTargetJointConf ( const Joint joint)

Gets the definition data for the given joint.

Exceptions
std::bad_castIf the given joint's type is inappropriate for getting this value.
Examples
TargetJoint.cpp.

◆ GetToi()

std::optional< UnitIntervalFF< Real > > playrho::d2::GetToi ( const World world,
ContactID  id 
)

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

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 empty.
Exceptions
std::out_of_rangeIf given an invalid contact identifier.
See also
HasValidToi.
Examples
WorldContact.cpp.

Referenced by playrho::d2::World::GetToi().

◆ GetToiCount()

TimestepIters playrho::d2::GetToiCount ( const World world,
ContactID  id 
)

Gets the Time Of Impact (TOI) count.

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

Referenced by playrho::d2::World::GetToiCount().

◆ GetToiViaSat()

ToiOutput playrho::d2::GetToiViaSat ( const DistanceProxy proxyA,
const Sweep sweepA,
const DistanceProxy proxyB,
const Sweep sweepB,
const ToiConf conf = GetDefaultToiConf() 
)

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

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

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

XXX maybe should return ToiOutput{timeLo, stats, ToiOutput::e_belowMinTarget}?

XXX maybe should return ToiOutput{timeLo, stats, ToiOutput::e_belowMinTarget}?

◆ GetTouchingCount()

ContactCounter playrho::d2::GetTouchingCount ( const World world)

Gets the touching count for the given world.

Basically a convenience function for iterating over all contact identifiers returned from GetContacts(const World&) for the given world and counting for how many IsTouching(const World&, ContactID) returns true.

See also
GetContacts(const World&), IsTouching(const World&, ContactID).
Examples
World.cpp, and WorldContact.cpp.

◆ GetTransform0()

Transformation playrho::d2::GetTransform0 ( const Sweep sweep)
inlinenoexcept

Gets the transform at "time" zero.

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

◆ GetTransform1()

Transformation playrho::d2::GetTransform1 ( const Sweep sweep)
inlinenoexcept

Gets the transform at "time" one.

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

Referenced by playrho::d2::Body::SetPosition1(), and playrho::d2::Body::SetSweep().

◆ GetTransformation() [1/3]

◆ GetTransformation() [2/3]

Transformation playrho::d2::GetTransformation ( const Sweep sweep,
const UnitIntervalFF< Real beta 
)
inlinenoexcept

Gets the interpolated transform at a specific time.

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

◆ GetTransformation() [3/3]

Transformation playrho::d2::GetTransformation ( const World world,
BodyID  id 
)

Gets the body's transformation.

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

◆ GetTree()

const DynamicTree & playrho::d2::GetTree ( const World world)
inline

Gets access to the broad-phase dynamic tree information.

Todo:
Consider removing this function. This function exposes the implementation detail of the broad-phase contact detection system.

◆ GetType() [1/6]

BodyType GetType ( const Body body)
inlinenoexcept

Gets the type of this body.

See also
SetType(Body&,BodyType).
Examples
Body.cpp, DistanceJoint.cpp, FrictionJoint.cpp, GearJoint.cpp, Joint.cpp, MotorJoint.cpp, PulleyJoint.cpp, RevoluteJoint.cpp, RopeJoint.cpp, Shape.cpp, WeldJoint.cpp, WheelJoint.cpp, World.cpp, WorldBody.cpp, and WorldShape.cpp.

Referenced by playrho::d2::Manifold::AddPoint(), playrho::d2::World::Awaken(), playrho::d2::Joint::EnableLimit(), playrho::d2::Joint::EnableMotor(), playrho::d2::Joint::GetAngularLowerLimit(), playrho::d2::Joint::GetAngularMass(), playrho::d2::Joint::GetAngularMotorImpulse(), playrho::d2::Joint::GetAngularOffset(), playrho::d2::Joint::GetAngularReaction(), playrho::d2::Joint::GetAngularUpperLimit(), playrho::d2::Body::GetBodyConf(), playrho::d2::Joint::GetDampingRatio(), playrho::d2::Joint::GetFrequency(), playrho::d2::World::GetGearJointConf(), playrho::d2::Joint::GetGroundAnchorA(), playrho::d2::Joint::GetGroundAnchorB(), playrho::d2::Joint::GetLength(), playrho::d2::Joint::GetLimitState(), playrho::d2::Joint::GetLinearLowerLimit(), playrho::d2::Joint::GetLinearMotorImpulse(), playrho::d2::Joint::GetLinearOffset(), playrho::d2::Joint::GetLinearReaction(), playrho::d2::Joint::GetLinearUpperLimit(), playrho::d2::Joint::GetLocalAnchorA(), playrho::d2::Joint::GetLocalAnchorB(), playrho::d2::Joint::GetLocalXAxisA(), playrho::d2::Joint::GetLocalYAxisA(), playrho::d2::Joint::GetMaxForce(), playrho::d2::Joint::GetMaxMotorForce(), playrho::d2::Joint::GetMaxMotorTorque(), playrho::d2::Joint::GetMaxTorque(), playrho::d2::Joint::GetMotorSpeed(), playrho::d2::Joint::GetRatio(), playrho::d2::Joint::GetReferenceAngle(), playrho::d2::Joint::GetTarget(), playrho::d2::World::GetType(), playrho::d2::Joint::IsLimitEnabled(), playrho::d2::Joint::IsMotorEnabled(), playrho::d2::Joint::SetAngularLimits(), playrho::d2::Joint::SetAngularOffset(), playrho::d2::Joint::SetFrequency(), playrho::d2::Joint::SetLinearLimits(), playrho::d2::Joint::SetLinearOffset(), playrho::d2::Joint::SetMaxMotorForce(), playrho::d2::Joint::SetMaxMotorTorque(), playrho::d2::Joint::SetMotorSpeed(), playrho::d2::Joint::SetTarget(), and playrho::d2::World::SetType().

◆ GetType() [2/6]

TypeID playrho::d2::GetType ( const Shape shape)
noexcept

Gets the type info of the use of the given shape.

Note
This is not the same as calling GetTypeID<Shape>().
Returns
Type info of the underlying value's type.

◆ GetType() [3/6]

TypeID playrho::d2::GetType ( const World world)
inlinenoexcept

Gets the identifier of the type of data the given world can be casted to.

Parameters
worldThe world for which an identifier of the type of its underlying value is to be returned.
See also
TypeCast.

◆ GetType() [4/6]

BodyType playrho::d2::GetType ( const World world,
BodyID  id 
)

Gets the type of the identified body.

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

◆ GetType() [5/6]

TypeID playrho::d2::GetType ( const World world,
JointID  id 
)

Gets the type of the joint.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetType() [6/6]

TypeID playrho::d2::GetType ( const World world,
ShapeID  id 
)

Gets the type of the shape.

Exceptions
std::out_of_rangeIf given an invalid identifier.

◆ GetUnderActiveTime()

Time GetUnderActiveTime ( const Body body)
inlinenoexcept

Gets the given body's under-active time.

Returns
Zero or more time in seconds (of step time) that this body has been "under-active" for.

Referenced by playrho::d2::Body::GetBodyConf(), and playrho::d2::Body::operator==().

◆ GetUnitVector()

template<class T >
UnitVec playrho::d2::GetUnitVector ( const Vector2< T > &  value,
const UnitVec fallback = UnitVec::GetDefaultFallback() 
)
inlinenoexcept

Gets the unit vector for the given value.

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

Referenced by playrho::d2::World::CalcGravitationalAcceleration(), GetFwdNormalsArray(), GetFwdNormalsVector(), GetMassData(), GetSeparationScenario(), playrho::d2::PulleyJointConf::InitVelocity(), RayCast(), playrho::d2::FrictionJointConf::SolveVelocity(), playrho::d2::MotorJointConf::SolveVelocity(), and playrho::d2::TargetJointConf::SolveVelocity().

◆ GetUsedShapesCount()

ShapeCounter playrho::d2::GetUsedShapesCount ( const World world)
noexcept

Gets the count of uniquely identified shapes that are in use - i.e. that are attached to bodies.

Parameters
worldThe world in which to get the used shapes count for.
See also
GetAssociationCount.
Examples
World.cpp.

◆ GetVelocity() [1/3]

◆ GetVelocity() [2/3]

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

Gets the velocity of the body after the given time accounting for the body's acceleration and capped by the given configuration.

Parameters
bodyBody to get the velocity for.
hTime elapsed to get velocity for.

◆ GetVelocity() [3/3]

Velocity playrho::d2::GetVelocity ( const World world,
BodyID  id 
)

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).

◆ GetVertexRadius()

NonNegative<Length> playrho::d2::GetVertexRadius ( const Shape shape,
ChildCounter  idx 
)

Gets the vertex radius of the indexed child of the given shape.

This gets the radius from the vertex that the shape's "skin" should extend outward by. While any edges - line segments between multiple vertices - are straight, corners between them (the vertices) are rounded and treated as rounded. Shapes with larger vertex radiuses compared to edge lengths therefore will be more prone to rolling or having other shapes more prone to roll off of them. Here's an image of a shape configured via a PolygonShapeConf with it's skin drawn:

Parameters
shapeShape to get child's vertex radius for.
idxChild index to get vertex radius for.
See also
UseVertexRadius
Exceptions
InvalidArgumentif the child index is not less than the child count.

◆ GetVertexRadiusInterval() [1/2]

Interval< Positive< Length > > playrho::d2::GetVertexRadiusInterval ( const AabbTreeWorld world)
inlinenoexcept

Gets the vertex radius interval allowable for the given world.

See also
CreateShape(AabbTreeWorld&, const Shape&).
Examples
World.cpp, and WorldBody.cpp.

Referenced by playrho::d2::detail::WorldModel< T >::GetVertexRadiusInterval_().

◆ GetVertexRadiusInterval() [2/2]

Interval< Positive< Length > > playrho::d2::GetVertexRadiusInterval ( const World world)
inlinenoexcept

Gets the vertex radius interval allowable for the given world.

Parameters
worldThe world whose allowable vertex radius interval is to be returned for.
See also
CreateShape(World&, const Shape&).

◆ GetWeldJointConf() [1/2]

WeldJointConf playrho::d2::GetWeldJointConf ( const Joint joint)

Gets the definition data for the given joint.

Exceptions
std::bad_castIf the given joint's type is inappropriate for getting this value.
Examples
WeldJoint.cpp, and World.cpp.

◆ GetWeldJointConf() [2/2]

WeldJointConf playrho::d2::GetWeldJointConf ( const World world,
BodyID  bodyA,
BodyID  bodyB,
const Length2 anchor = Length2{} 
)

Gets the configuration for the given parameters.

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ GetWheelJointConf() [1/2]

WheelJointConf playrho::d2::GetWheelJointConf ( const Joint joint)

Gets the definition data for the given joint.

Exceptions
std::bad_castIf the given joint's type is inappropriate for getting this value.
Examples
WheelJoint.cpp.

◆ GetWheelJointConf() [2/2]

WheelJointConf playrho::d2::GetWheelJointConf ( const World world,
BodyID  bodyA,
BodyID  bodyB,
const Length2 anchor,
const UnitVec axis = UnitVec::GetRight() 
)

Gets the definition data for the given parameters.

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ GetWorldCenter()

Length2 playrho::d2::GetWorldCenter ( const World world,
BodyID  id 
)

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 playrho::d2::GetWorldIndex ( const World ,
BodyID  id 
)
noexcept

Gets the world index for the given body.

Exceptions
std::out_of_rangeIf given an invalid body identifier.
Examples
RevoluteJoint.cpp, and WorldBody.cpp.

◆ GetWorldIndex() [2/2]

JointCounter playrho::d2::GetWorldIndex ( const World ,
JointID  id 
)
noexcept

Gets the world index of the given joint.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetWorldManifold() [1/3]

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

Gets the world manifold for the given data.

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

◆ GetWorldManifold() [2/3]

WorldManifold playrho::d2::GetWorldManifold ( const World world,
const Contact contact,
const Manifold manifold 
)

Gets the world manifold for the given data.

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

◆ GetWorldManifold() [3/3]

WorldManifold playrho::d2::GetWorldManifold ( const World world,
ContactID  id 
)

Gets the world manifold for the identified contact.

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

Referenced by playrho::Contact::GetWorldManifold(), and playrho::d2::World::GetWorldManifold().

◆ GetWorldPoint() [1/2]

Length2 GetWorldPoint ( const Body body,
const Length2 localPoint 
)
inlinenoexcept

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

Parameters
bodyBody that the given point is relative to.
localPointa point measured relative the the body's origin.
Returns
the same point expressed in world coordinates.
Examples
GearJoint.cpp, and PulleyJoint.cpp.

Referenced by playrho::d2::Body::GetLinearVelocityFromLocalPoint(), and playrho::d2::World::RotateAboutLocalPoint().

◆ GetWorldPoint() [2/2]

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

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.

◆ GetWorldVector() [1/2]

Length2 GetWorldVector ( const Body body,
const Length2 localVector 
)
inlinenoexcept

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

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

◆ GetWorldVector() [2/2]

UnitVec GetWorldVector ( const World world,
BodyID  id,
const UnitVec localVector 
)
inline

Convenience function for getting a world vector of the identified body.

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ GetYAxis()

constexpr UnitVec playrho::d2::GetYAxis ( const UnitVec rot)
constexprnoexcept

Gets the "Y-axis".

Note
This is the reverse perpendicular vector of the given unit vector.

◆ HasValidToi()

bool playrho::d2::HasValidToi ( const World world,
ContactID  id 
)

Whether or not the contact has a valid TOI.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.
See also
GetToi.
Examples
World.cpp, and WorldContact.cpp.

Referenced by playrho::d2::World::HasValidToi().

◆ InitVelocity() [1/12]

void playrho::d2::InitVelocity ( DistanceJointConf object,
const Span< BodyConstraint > &  bodies,
const StepConf step,
const ConstraintSolverConf conf 
)

Initializes velocity constraint data based on the given solver data.

Note
This MUST be called prior to calling SolveVelocity.
Parameters
objectConfiguration object. bodyA and bodyB must index bodies within the given bodies container or be the special body ID value of InvalidBodyID.
bodiesContainer of body constraints.
stepConfiguration for the step.
confConstraint solver configuration.
Exceptions
std::out_of_rangeIf the given object's bodyA or bodyB values are not InvalidBodyID and are not indices within range of the given bodies container.
See also
SolveVelocity.
Examples
DistanceJoint.cpp, FrictionJoint.cpp, GearJoint.cpp, MotorJoint.cpp, PrismaticJoint.cpp, PulleyJoint.cpp, RevoluteJoint.cpp, RopeJoint.cpp, TargetJoint.cpp, WeldJoint.cpp, and WheelJoint.cpp.

Referenced by playrho::d2::detail::JointModel< T >::InitVelocity_().

◆ InitVelocity() [2/12]

void playrho::d2::InitVelocity ( FrictionJointConf object,
const Span< BodyConstraint > &  bodies,
const StepConf step,
const ConstraintSolverConf conf 
)

Initializes velocity constraint data based on the given solver data.

Note
This MUST be called prior to calling SolveVelocity.
Parameters
objectConfiguration object. bodyA and bodyB must index bodies within the given bodies container or be the special body ID value of InvalidBodyID.
bodiesContainer of body constraints.
stepConfiguration for the step.
confConstraint solver configuration.
Exceptions
std::out_of_rangeIf the given object's bodyA or bodyB values are not InvalidBodyID and are not indices within range of the given bodies container.
See also
SolveVelocity.

◆ InitVelocity() [3/12]

void playrho::d2::InitVelocity ( GearJointConf object,
const Span< BodyConstraint > &  bodies,
const StepConf step,
const ConstraintSolverConf conf 
)

Initializes velocity constraint data based on the given solver data.

Note
This MUST be called prior to calling SolveVelocity.
Parameters
objectConfiguration object. bodyA and bodyB must index bodies within the given bodies container or be the special body ID value of InvalidBodyID.
bodiesContainer of body constraints.
stepConfiguration for the step.
confConstraint solver configuration.
Exceptions
std::out_of_rangeIf the given object's bodyA or bodyB values are not InvalidBodyID and are not indices within range of the given bodies container.
See also
SolveVelocity.

◆ InitVelocity() [4/12]

void playrho::d2::InitVelocity ( Joint object,
const Span< BodyConstraint > &  bodies,
const StepConf step,
const ConstraintSolverConf conf 
)

Initializes velocity constraint data based on the given solver data.

Note
This MUST be called prior to calling SolveVelocity.
See also
SolveVelocity.

◆ InitVelocity() [5/12]

void playrho::d2::InitVelocity ( MotorJointConf object,
const Span< BodyConstraint > &  bodies,
const StepConf step,
const ConstraintSolverConf conf 
)

Initializes velocity constraint data based on the given solver data.

Note
This MUST be called prior to calling SolveVelocity.
Parameters
objectConfiguration object. bodyA and bodyB must index bodies within the given bodies container or be the special body ID value of InvalidBodyID.
bodiesContainer of body constraints.
stepConfiguration for the step.
confConstraint solver configuration.
Exceptions
std::out_of_rangeIf the given object's bodyA or bodyB values are not InvalidBodyID and are not indices within range of the given bodies container.
See also
SolveVelocity.

◆ InitVelocity() [6/12]

void playrho::d2::InitVelocity ( PrismaticJointConf object,
const Span< BodyConstraint > &  bodies,
const StepConf step,
const ConstraintSolverConf conf 
)

Initializes velocity constraint data based on the given solver data.

Note
This MUST be called prior to calling SolveVelocity.
Parameters
objectConfiguration object. bodyA and bodyB must index bodies within the given bodies container or be the special body ID value of InvalidBodyID.
bodiesContainer of body constraints.
stepConfiguration for the step.
confConstraint solver configuration.
Exceptions
std::out_of_rangeIf the given object's bodyA or bodyB values are not InvalidBodyID and are not indices within range of the given bodies container.
See also
SolveVelocityConstraints.

◆ InitVelocity() [7/12]

void playrho::d2::InitVelocity ( PulleyJointConf object,
const Span< BodyConstraint > &  bodies,
const StepConf step,
const ConstraintSolverConf conf 
)

Initializes velocity constraint data based on the given solver data.

Note
This MUST be called prior to calling SolveVelocity.
Parameters
objectConfiguration object. bodyA and bodyB must index bodies within the given bodies container or be the special body ID value of InvalidBodyID.
bodiesContainer of body constraints.
stepConfiguration for the step.
confConstraint solver configuration.
Exceptions
std::out_of_rangeIf the given object's bodyA or bodyB values are not InvalidBodyID and are not indices within range of the given bodies container.
See also
SolveVelocity.

◆ InitVelocity() [8/12]

void playrho::d2::InitVelocity ( RevoluteJointConf object,
const Span< BodyConstraint > &  bodies,
const StepConf step,
const ConstraintSolverConf conf 
)

Initializes velocity constraint data based on the given solver data.

Note
This MUST be called prior to calling SolveVelocity.
Parameters
objectConfiguration object. bodyA and bodyB must index bodies within the given bodies container or be the special body ID value of InvalidBodyID.
bodiesContainer of body constraints.
stepConfiguration for the step.
confConstraint solver configuration.
Exceptions
std::out_of_rangeIf the given object's bodyA or bodyB values are not InvalidBodyID and are not indices within range of the given bodies container.
See also
SolveVelocityConstraints.

◆ InitVelocity() [9/12]

void playrho::d2::InitVelocity ( RopeJointConf object,
const Span< BodyConstraint > &  bodies,
const StepConf step,
const ConstraintSolverConf conf 
)

Initializes velocity constraint data based on the given solver data.

Note
This MUST be called prior to calling SolveVelocity.
Parameters
objectConfiguration object. bodyA and bodyB must index bodies within the given bodies container or be the special body ID value of InvalidBodyID.
bodiesContainer of body constraints.
stepConfiguration for the step.
confConstraint solver configuration.
Exceptions
std::out_of_rangeIf the given object's bodyA or bodyB values are not InvalidBodyID and are not indices within range of the given bodies container.
See also
SolveVelocity.

◆ InitVelocity() [10/12]

void playrho::d2::InitVelocity ( TargetJointConf object,
const Span< BodyConstraint > &  bodies,
const StepConf step,
const ConstraintSolverConf conf 
)

Initializes velocity constraint data based on the given solver data.

Note
This MUST be called prior to calling SolveVelocity.
Parameters
objectConfiguration object. bodyB must index a body within the given bodies container or be the special body ID value of InvalidBodyID.
bodiesContainer of body constraints.
stepConfiguration for the step.
confConstraint solver configuration.
Exceptions
std::out_of_rangeIf the given object's bodyB value is not InvalidBodyID and does not index within range of the given bodies container.
See also
SolveVelocity.

◆ InitVelocity() [11/12]

void playrho::d2::InitVelocity ( WeldJointConf object,
const Span< BodyConstraint > &  bodies,
const StepConf step,
const ConstraintSolverConf conf 
)

Initializes velocity constraint data based on the given solver data.

Note
This MUST be called prior to calling SolveVelocity.
Parameters
objectConfiguration object. bodyA and bodyB must index bodies within the given bodies container or be the special body ID value of InvalidBodyID.
bodiesContainer of body constraints.
stepConfiguration for the step.
confConstraint solver configuration.
Exceptions
std::out_of_rangeIf the given object's bodyA or bodyB values are not InvalidBodyID and are not indices within range of the given bodies container.
See also
SolveVelocity.

◆ InitVelocity() [12/12]

void playrho::d2::InitVelocity ( WheelJointConf object,
const Span< BodyConstraint > &  bodies,
const StepConf step,
const ConstraintSolverConf conf 
)

Initializes velocity constraint data based on the given solver data.

Note
This MUST be called prior to calling SolveVelocity.
Parameters
objectConfiguration object. bodyA and bodyB must index bodies within the given bodies container or be the special body ID value of InvalidBodyID.
bodiesContainer of body constraints.
stepConfiguration for the step.
confConstraint solver configuration.
Exceptions
std::out_of_rangeIf the given object's bodyA or bodyB values are not InvalidBodyID and are not indices within range of the given bodies container.
See also
SolveVelocity.

◆ InverseRotate()

template<class T >
constexpr auto playrho::d2::InverseRotate ( const Vector2< T > &  vector,
const UnitVec angle 
)
constexprnoexcept

Inverse rotates a vector.

This is the inverse of rotating a vector - it undoes what rotate does. I.e. this effectively subtracts from the angle of the given vector the angle that's expressed by the angle parameter.

Parameters
vectorVector to reverse rotate.
angleExpresses the angle to reverse rotate the given vector by.
See also
Rotate.

Referenced by playrho::d2::DistanceProxy::Distance(), playrho::d2::World::GetGearJointConf(), playrho::d2::Body::GetLocalVector(), playrho::d2::World::GetLocalVector(), InverseTransform(), MulT(), and playrho::d2::GearJointConf::SolvePosition().

◆ InverseTransform()

constexpr Length2 playrho::d2::InverseTransform ( const Length2 v,
const Transformation xfm 
)
constexprnoexcept

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

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

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

Referenced by playrho::d2::Body::GetLocalPoint(), playrho::d2::World::GetLocalPoint(), GetManifold(), playrho::d2::DistanceProxy::RayCast(), and playrho::d2::World::TestPoint().

◆ IsAccelerable() [1/2]

bool IsAccelerable ( const Body body)
inlinenoexcept

Is "accelerable".

Indicates whether this 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.
See also
GetType(const Body& body), SetType(Body& body, BodyType value).
Examples
World.cpp, and WorldBody.cpp.

Referenced by playrho::d2::Body::GetBodyConf(), playrho::d2::World::IsAccelerable(), and playrho::d2::World::SetMassData().

◆ IsAccelerable() [2/2]

bool playrho::d2::IsAccelerable ( const World world,
BodyID  id 
)

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 Body body)
inlinenoexcept

◆ IsAwake() [2/3]

bool playrho::d2::IsAwake ( const World world,
BodyID  id 
)

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() [3/3]

bool playrho::d2::IsAwake ( const World world,
ContactID  id 
)

Gets the awake status of the specified contact.

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

◆ IsBranch()

constexpr bool IsBranch ( const DynamicTree::TreeNode node)
constexprnoexcept

Is branch.

Determines whether the given dynamic tree node is a branch node. Branch nodes have 2 indices to child nodes.

Determines whether the given node is a "branch" node.

Referenced by playrho::d2::DynamicTree::FindReference(), and playrho::d2::DynamicTree::GetBranchData().

◆ IsDestroyed() [1/9]

auto playrho::d2::IsDestroyed ( const AabbTreeWorld world,
BodyID  id 
) -> bool
inline

Gets whether the given identifier is to a body that's been destroyed.

Note
Complexity of this function is O(1).
See also
Destroy(AabbTreeWorld& world, BodyID).
Examples
Body.cpp, and World.cpp.

Referenced by IsDestroyed().

◆ IsDestroyed() [2/9]

auto playrho::d2::IsDestroyed ( const AabbTreeWorld world,
ContactID  id 
) -> bool
inline

Gets whether the given identifier is to a contact that's been destroyed.

Note
Complexity of this function is O(1).

◆ IsDestroyed() [3/9]

auto playrho::d2::IsDestroyed ( const AabbTreeWorld world,
JointID  id 
) -> bool
inline

Gets whether the given identifier is to a joint that's been destroyed.

Note
Complexity is O(1).
See also
Destroy(AabbTreeWorld& world, JointID).

◆ IsDestroyed() [4/9]

auto playrho::d2::IsDestroyed ( const AabbTreeWorld world,
ShapeID  id 
) -> bool
inline

Gets whether the given identifier is to a shape that's been destroyed.

Note
Complexity is O(1).
See also
Destroy(AabbTreeWorld& world, ShapeID).

◆ IsDestroyed() [5/9]

constexpr auto playrho::d2::IsDestroyed ( const Body body) -> bool
constexprnoexcept

Whether or not the given body was destroyed.

See also
SetDestroyed, UnsetDestroyed.

◆ IsDestroyed() [6/9]

auto playrho::d2::IsDestroyed ( const World world,
BodyID  id 
) -> bool
inline

Gets whether the given identifier is to a body that's been destroyed.

Note
Complexity of this function is O(1).
See also
Destroy(World& world, BodyID).

◆ IsDestroyed() [7/9]

auto playrho::d2::IsDestroyed ( const World world,
ContactID  id 
) -> bool
inline

Gets whether the given identifier is to a contact that's been destroyed.

Note
Complexity of this function is O(1).

◆ IsDestroyed() [8/9]

auto playrho::d2::IsDestroyed ( const World world,
JointID  id 
) -> bool
inline

Gets whether the given identifier is to a joint that's been destroyed.

Note
Complexity of this function is O(1).

◆ IsDestroyed() [9/9]

auto playrho::d2::IsDestroyed ( const World world,
ShapeID  id 
) -> bool
inline

Gets whether the given identifier is to a shape that's been destroyed.

Note
Complexity of this function is O(1).

◆ IsEnabled() [1/4]

bool IsEnabled ( const Body body)
inlinenoexcept

◆ IsEnabled() [2/4]

bool playrho::d2::IsEnabled ( const World world,
BodyID  id 
)

Gets the enabled/disabled state of the body.

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

◆ IsEnabled() [3/4]

bool playrho::d2::IsEnabled ( const World world,
ContactID  id 
)

Gets the enabled status of the identified contact.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.

◆ IsEnabled() [4/4]

bool playrho::d2::IsEnabled ( const World world,
JointID  id 
)

Gets the enabled/disabled state of the joint.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ IsFixedRotation() [1/2]

◆ IsFixedRotation() [2/2]

bool playrho::d2::IsFixedRotation ( const World world,
BodyID  id 
)

Gets whether the body has fixed rotation.

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

◆ IsImpenetrable() [1/2]

bool IsImpenetrable ( const Body body)
inlinenoexcept

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

See also
SetImpenetrable(Body&).
Examples
World.cpp, WorldBody.cpp, and WorldContact.cpp.

Referenced by playrho::d2::Body::GetBodyConf(), and playrho::d2::World::IsImpenetrable().

◆ IsImpenetrable() [2/2]

bool playrho::d2::IsImpenetrable ( const World world,
BodyID  id 
)

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

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ IsLeaf()

constexpr bool IsLeaf ( const DynamicTree::TreeNode node)
constexprnoexcept

Is leaf.

Whether or not this node is a leaf node.

Determines whether the given dynamic tree node is a leaf node.

Note
This has constant complexity.
Returns
true if this is a leaf node, false otherwise.

Referenced by playrho::d2::DynamicTree::DestroyLeaf(), playrho::d2::DynamicTree::FindIndex(), and playrho::d2::DynamicTree::GetLeafData().

◆ IsLimitEnabled() [1/2]

bool playrho::d2::IsLimitEnabled ( const Joint object)

Gets the specified joint's limit property if it supports one.

Exceptions
std::invalid_argumentIf not supported for the given joint's type.
Examples
Joint.cpp, PrismaticJoint.cpp, and RevoluteJoint.cpp.

Referenced by playrho::d2::Joint::IsLimitEnabled(), and playrho::d2::World::IsLimitEnabled().

◆ IsLimitEnabled() [2/2]

bool playrho::d2::IsLimitEnabled ( const World world,
JointID  id 
)

Gets whether the identified joint's limit is enabled.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ IsLocked()

bool playrho::d2::IsLocked ( const World world)
inlinenoexcept

Is the specified world locked.

Used to detect whether being called while already within the execution of the Step(World&, const StepConf&) function - which sets this "lock".

Parameters
worldThe world to return whether it's in a locked state or not.
See also
Step(World&, const StepConf&).

◆ IsMassDataDirty()

bool playrho::d2::IsMassDataDirty ( const World world,
BodyID  id 
)

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

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ IsMotorEnabled() [1/2]

bool playrho::d2::IsMotorEnabled ( const Joint object)

Gets the specified joint's motor property value if it supports one.

Exceptions
std::invalid_argumentIf not supported for the given joint's type.
Examples
Joint.cpp, PrismaticJoint.cpp, RevoluteJoint.cpp, and WheelJoint.cpp.

Referenced by playrho::d2::Joint::IsMotorEnabled(), and playrho::d2::World::IsMotorEnabled().

◆ IsMotorEnabled() [2/2]

bool playrho::d2::IsMotorEnabled ( const World world,
JointID  id 
)

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() [1/2]

bool playrho::d2::IsSensor ( const Shape shape)
noexcept

◆ IsSensor() [2/2]

bool playrho::d2::IsSensor ( const World world,
ShapeID  id 
)

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

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

◆ IsSleepingAllowed() [1/2]

bool IsSleepingAllowed ( const Body body)
inlinenoexcept

Gets whether or not this body allowed to sleep.

See also
SetSleepingAllowed(Body&).
Examples
Body.cpp, and World.cpp.

Referenced by playrho::d2::Body::GetBodyConf(), playrho::d2::World::IsSleepingAllowed(), playrho::d2::Body::operator==(), and playrho::d2::Body::Unawaken().

◆ IsSleepingAllowed() [2/2]

bool playrho::d2::IsSleepingAllowed ( const World world,
BodyID  id 
)

Gets whether the identified body is allowed to sleep.

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ IsSpeedable() [1/2]

bool IsSpeedable ( const Body body)
inlinenoexcept

Is "speedable".

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

Examples
Body.cpp, World.cpp, and WorldBody.cpp.

Referenced by playrho::d2::Body::Awaken(), playrho::d2::World::Awaken(), playrho::d2::World::IsSpeedable(), and playrho::d2::World::SetMassData().

◆ IsSpeedable() [2/2]

bool playrho::d2::IsSpeedable ( const World world,
BodyID  id 
)

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.

◆ IsStepComplete() [1/2]

bool playrho::d2::IsStepComplete ( const AabbTreeWorld world)
inlinenoexcept

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 function returned without finishing all of its sub-steps.
See also
GetSubStepping, SetSubStepping.
Examples
World.cpp.

Referenced by playrho::d2::detail::WorldModel< T >::IsStepComplete_().

◆ IsStepComplete() [2/2]

bool playrho::d2::IsStepComplete ( const World world)
inlinenoexcept

Whether or not "step" is complete.

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

Parameters
worldThe world to return whether the step is completed for.
Returns
true unless sub-stepping is enabled and the step function returned without finishing all of its sub-steps.
See also
GetSubStepping, SetSubStepping, Step.

◆ IsTouching()

bool playrho::d2::IsTouching ( const World world,
ContactID  id 
)

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.
Examples
World.cpp.

Referenced by playrho::d2::World::GetTouchingCount(), and playrho::d2::World::IsTouching().

◆ IsUnused()

constexpr bool IsUnused ( const DynamicTree::TreeNode node)
constexprnoexcept

Is unused.

Whether this node is free (or allocated).

Determines whether the given dynamic tree node is an unused node.

Referenced by playrho::d2::DynamicTree::DestroyLeaf(), playrho::d2::DynamicTree::TreeNode::GetAABB(), playrho::d2::DynamicTree::GetAABB(), playrho::d2::DynamicTree::TreeNode::GetNext(), and playrho::d2::DynamicTree::ShiftOrigin().

◆ Mul()

constexpr Transformation playrho::d2::Mul ( const Transformation A,
const Transformation B 
)
constexprnoexcept

Multiplies a given transformation by another given transformation.

Note
v2 = A.q.Rot(B.q.Rot(v1) + B.p) + A.p = (A.q * B.q).Rot(v1) + A.q.Rot(B.p) + A.p

◆ MulT()

constexpr Transformation playrho::d2::MulT ( const Transformation A,
const Transformation B 
)
constexprnoexcept

Inverse multiplies a given transformation by another given transformation.

Note
v2 = A.q' * (B.q * v1 + B.p - A.p) = A.q' * B.q * v1 + A.q' * (B.p - A.p)

Referenced by playrho::d2::DistanceProxy::GetMaxSeparation(), and playrho::d2::DistanceProxy::GetMaxSeparation4x4().

◆ NeedsFiltering()

bool playrho::d2::NeedsFiltering ( const World world,
ContactID  id 
)

Whether or not the contact needs filtering.

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

Referenced by playrho::d2::World::NeedsFiltering().

◆ NeedsUpdating()

bool playrho::d2::NeedsUpdating ( const World world,
ContactID  id 
)

Whether or not the contact needs updating.

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

Referenced by playrho::d2::World::NeedsUpdating().

◆ operator!=() [1/3]

bool operator!= ( const Body lhs,
const Body rhs 
)
inline

Not-equals operator.

See also
operator==(const Body&, const Body&).

◆ operator!=() [2/3]

bool playrho::d2::operator!= ( const Manifold lhs,
const Manifold rhs 
)
noexcept

Manifold inequality operator.

Determines whether the two given manifolds are not equal.

◆ operator!=() [3/3]

bool playrho::d2::operator!= ( const World lhs,
const World rhs 
)
inlinenoexcept

Inequality operator for world comparisons.

Parameters
lhsLeft hand side world of the infix binary inequality operator.
rhsRight hand side world of the infix binary inequality operator.
Returns
true if lhs is not equal to rhs , false otherwise.

◆ operator==() [1/3]

bool playrho::d2::operator== ( const Body lhs,
const Body rhs 
)

Equals operator.

See also
operator!=(const Body&, const Body&).

◆ operator==() [2/3]

bool playrho::d2::operator== ( const Manifold lhs,
const Manifold rhs 
)
noexcept

Manifold equality operator.

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

◆ operator==() [3/3]

bool playrho::d2::operator== ( const World lhs,
const World rhs 
)
inlinenoexcept

Equality operator for world comparisons.

Parameters
lhsLeft hand side world of the infix binary equality operator.
rhsRight hand side world of the infix binary equality operator.
Returns
true if lhs is equal to rhs , false otherwise.

◆ Query() [1/2]

void playrho::d2::Query ( const DynamicTree tree,
const AABB aabb,
const DynamicTreeSizeCB callback 
)

Query the given dynamic tree and find nodes overlapping the given AABB.

Note
The callback instance is called for each leaf node that overlaps the supplied AABB.
Examples
World.cpp.

Referenced by Query().

◆ Query() [2/2]

void playrho::d2::Query ( const DynamicTree tree,
const AABB aabb,
QueryShapeCallback  callback 
)

Queries the world for all fixtures that potentially overlap the provided AABB.

Parameters
treeDynamic tree to do the query over.
aabbThe query box.
callbackUser implemented callback function.

◆ ReplaceChild()

constexpr DynamicTreeBranchData playrho::d2::ReplaceChild ( DynamicTreeBranchData  bd,
DynamicTree::Size  oldChild,
DynamicTree::Size  newChild 
)
constexpr

Replaces the old child with the new child.

Precondition
Either bd.child1 or bd.child2 is equal to oldChild .

◆ ResetFriction()

void ResetFriction ( World world,
ContactID  id 
)
inline

Resets the friction mixture to the default value.

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

◆ ResetMassData()

void playrho::d2::ResetMassData ( World world,
BodyID  id 
)

Resets the mass data properties.

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

Note
This function must be called after associating new shapes to the body to update the body mass data properties unless SetMassData is used.
Exceptions
WrongStateif this function is called while the world is locked.
std::out_of_rangeIf given an invalid body identifier.
See also
SetMassData, Attach, Detach.
Examples
WorldBody.cpp.

Referenced by playrho::d2::World::Attach(), playrho::d2::World::Detach(), playrho::d2::World::SetFixedRotation(), and playrho::d2::World::SetType().

◆ ResetRestitution()

void ResetRestitution ( World world,
ContactID  id 
)
inline

Resets the restitution to the default value.

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

◆ Rotate() [1/4]

constexpr UnitVec playrho::d2::Rotate ( const UnitVec vector,
const UnitVec angle 
)
constexprnoexcept

Rotates a unit vector by the angle expressed by the second unit vector.

Returns
Unit vector for the angle that's the sum of the two angles expressed by the input unit vectors.

◆ Rotate() [2/4]

template<class T >
constexpr auto playrho::d2::Rotate ( const Vector2< T > &  vector,
const UnitVec angle 
)
constexprnoexcept

Rotates a vector by a given angle.

This rotates a vector by the angle expressed by the angle parameter.

Parameters
vectorVector to forward rotate.
angleExpresses the angle to forward rotate the given vector by.
See also
InverseRotate.

◆ Rotate() [3/4]

void playrho::d2::Rotate ( Shape shape,
const UnitVec value 
)

Rotates all of the given shape's vertices by the given amount.

Note
This may throw std::bad_alloc or any exception that's thrown by the constructor for the model's underlying data type.
Exceptions
std::bad_allocif there's a failure allocating storage.

◆ Rotate() [4/4]

void playrho::d2::Rotate ( World world,
ShapeID  id,
const UnitVec value 
)

Rotates all of the given shape's vertices by the given amount.

Note
This may throw std::bad_alloc or any exception that's thrown by the constructor for the model's underlying data type.
Exceptions
std::bad_allocif there's a failure allocating storage.
std::out_of_rangeIf given an invalid identifier.

◆ RotateAboutLocalPoint()

void playrho::d2::RotateAboutLocalPoint ( World world,
BodyID  id,
Angle  amount,
const Length2 localPoint 
)

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

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

Note
Manipulating a body's position this way may cause non-physical behavior.
This is a convenience function that translates the local point into world coordinates and then calls the RotateAboutWorldPoint function.
Parameters
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
WrongStateif this function is called while the world is locked.
std::out_of_rangeIf given an invalid body identifier.
Examples
WorldBody.cpp.

◆ RotateAboutWorldPoint()

void playrho::d2::RotateAboutWorldPoint ( World world,
BodyID  id,
Angle  amount,
const Length2 worldPoint 
)

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

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

Note
Manipulating a body's position this way may cause non-physical behavior.
Parameters
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
WrongStateif this function is called while the world is locked.
std::out_of_rangeIf given an invalid body identifier.
Examples
WorldBody.cpp.

Referenced by playrho::d2::World::RotateAboutLocalPoint().

◆ Scale() [1/2]

void playrho::d2::Scale ( Shape shape,
const Vec2 value 
)

Scales all of the given shape's vertices by the given amount.

Note
This may throw std::bad_alloc or any exception that's thrown by the constructor for the model's underlying data type.
Exceptions
std::bad_allocif there's a failure allocating storage.

◆ Scale() [2/2]

void playrho::d2::Scale ( World world,
ShapeID  id,
const Vec2 value 
)

Scales all of the given shape's vertices by the given amount.

Note
This may throw std::bad_alloc or any exception that's thrown by the constructor for the model's underlying data type.
Exceptions
std::bad_allocif there's a failure allocating storage.
std::out_of_rangeIf given an invalid identifier.

◆ SetAcceleration() [1/8]

void SetAcceleration ( Body body,
AngularAcceleration  value 
)
inlinenoexcept

Sets the given angular acceleration of the given body.

See also
GetAcceleration(const Body& body).

◆ SetAcceleration() [2/8]

void SetAcceleration ( Body body,
const Acceleration value 
)
inlinenoexcept

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
bodyBody whose acceleration should be set.
valueAcceleration value to set.
See also
GetAcceleration(const Body& body).
Examples
World.cpp, and WorldBody.cpp.

Referenced by playrho::d2::World::ApplyForce(), playrho::d2::World::ApplyForceToCenter(), playrho::d2::World::ApplyTorque(), playrho::d2::World::SetAcceleration(), playrho::d2::World::SetAccelerations(), playrho::d2::World::SetForce(), and playrho::d2::World::SetTorque().

◆ SetAcceleration() [3/8]

void SetAcceleration ( Body body,
const LinearAcceleration2 linear,
AngularAcceleration  angular 
)
inlinenoexcept

Sets the linear and rotational accelerations on this body.

Note
This has no effect on non-accelerable bodies.
A non-zero acceleration will also awaken the body.
Parameters
bodyBody to set the acceleration of.
linearLinear acceleration.
angularAngular acceleration.
See also
GetAcceleration(const Body& body).

◆ SetAcceleration() [4/8]

void SetAcceleration ( Body body,
const LinearAcceleration2 value 
)
inlinenoexcept

Sets the given linear acceleration of the given body.

See also
GetAcceleration(const Body& body).

◆ SetAcceleration() [5/8]

void playrho::d2::SetAcceleration ( World world,
BodyID  id,
AngularAcceleration  value 
)

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
WrongStateif this function is called while the world is locked.
std::out_of_rangeIf given an invalid body identifier.
See also
GetAcceleration(const World& world, BodyID id).

◆ SetAcceleration() [6/8]

void playrho::d2::SetAcceleration ( World world,
BodyID  id,
const Acceleration value 
)

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
WrongStateif this function is called while the world is locked.
std::out_of_rangeIf given an invalid body identifier.
See also
GetAcceleration(const World& world, BodyID id).

◆ SetAcceleration() [7/8]

void playrho::d2::SetAcceleration ( World world,
BodyID  id,
const LinearAcceleration2 linear,
AngularAcceleration  angular 
)

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
WrongStateif this function is called while the world is locked.
std::out_of_rangeIf given an invalid body identifier.
See also
GetAcceleration(const World& world, BodyID id).

◆ SetAcceleration() [8/8]

void playrho::d2::SetAcceleration ( World world,
BodyID  id,
const LinearAcceleration2 value 
)

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
WrongStateif this function is called while the world is locked.
std::out_of_rangeIf given an invalid body identifier.
See also
GetAcceleration(const World& world, BodyID id).

◆ SetAccelerations() [1/3]

void playrho::d2::SetAccelerations ( World world,
const Acceleration acceleration 
)

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

Exceptions
WrongStateif this function is called while the world is locked.

◆ SetAccelerations() [2/3]

void playrho::d2::SetAccelerations ( World world,
const LinearAcceleration2 acceleration 
)

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

Note
This will leave the angular acceleration alone.
Exceptions
WrongStateif this function is called while the world is locked.

◆ SetAccelerations() [3/3]

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

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).
Exceptions
WrongStateif this function is called while the world is locked.
Postcondition
On success: GetAcceleration(const World&, BodyID) will return the acceleration assigned to it by the given function.
See also
SetAcceleration(World&,BodyID,const Acceleration&), GetAcceleration(const World&,BodyID).
Examples
DistanceJoint.cpp, RevoluteJoint.cpp, and World.cpp.

Referenced by playrho::d2::World::ClearForces().

◆ SetAngle() [1/2]

void playrho::d2::SetAngle ( Body body,
Angle  value 
)

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
bodyThe body to update.
valueValid world angle of the body's local origin.
See also
GetAngle(const Body& body).
Examples
World.cpp, and WorldBody.cpp.

Referenced by playrho::d2::World::SetAngle().

◆ SetAngle() [2/2]

void playrho::d2::SetAngle ( World world,
BodyID  id,
Angle  value 
)

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.
Exceptions
WrongStateif this function is called while the world is locked.
std::out_of_rangeIf given an invalid body identifier.
See also
GetAngle(const World& world, BodyID id).

◆ SetAngularDamping() [1/2]

void SetAngularDamping ( Body body,
NonNegative< Frequency value 
)
inlinenoexcept

Sets the angular damping of the body.

See also
GetAngularDamping(const Body& body).
Examples
Body.cpp, and World.cpp.

Referenced by playrho::d2::World::SetAngularDamping().

◆ SetAngularDamping() [2/2]

void playrho::d2::SetAngularDamping ( World world,
BodyID  id,
NonNegative< Frequency angularDamping 
)

Sets the angular damping of the body.

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

◆ SetAngularLimits() [1/2]

void playrho::d2::SetAngularLimits ( Joint object,
Angle  lower,
Angle  upper 
)

Sets the joint limits.

Exceptions
std::invalid_argumentIf not supported for the given joint's type.
Examples
Joint.cpp, and RevoluteJoint.cpp.

Referenced by playrho::d2::World::SetAngularLimits().

◆ SetAngularLimits() [2/2]

void playrho::d2::SetAngularLimits ( World world,
JointID  id,
Angle  lower,
Angle  upper 
)

Set the joint limits.

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

◆ SetAngularOffset() [1/2]

void playrho::d2::SetAngularOffset ( Joint object,
Angle  value 
)

Sets the angular offset property of the specified joint if its type has one.

Exceptions
std::invalid_argumentIf not supported for the given joint's type.
Examples
MotorJoint.cpp, and PrismaticJoint.cpp.

Referenced by playrho::d2::World::SetAngularOffset().

◆ SetAngularOffset() [2/2]

void playrho::d2::SetAngularOffset ( World world,
JointID  id,
Angle  value 
)

Sets the target angular offset.

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

◆ SetAwake() [1/4]

void SetAwake ( Body body)
inlinenoexcept

Awakens this body.

Sets this body to awake and resets its under-active time if it's a "speedable" body. This function has no effect otherwise.

Postcondition
If this body is a "speedable" body, then IsAwake(const Body&) function returns true.
If this body is a "speedable" body, then this body's GetUnderActiveTime function returns zero.
See also
IsAwake(const Body&), UnsetAwake(Body&).
Examples
RevoluteJoint.cpp, World.cpp, WorldBody.cpp, and WorldContact.cpp.

Referenced by playrho::d2::World::Awaken(), and playrho::d2::World::SetAwake().

◆ SetAwake() [2/4]

void playrho::d2::SetAwake ( World world,
BodyID  id 
)

Wakes up the identified body.

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

◆ SetAwake() [3/4]

void playrho::d2::SetAwake ( World world,
ContactID  id 
)

Sets awake the bodies of the given contact.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.

◆ SetAwake() [4/4]

void playrho::d2::SetAwake ( World world,
JointID  id 
)

Wakes up the joined bodies.

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

◆ SetBeginContactListener()

void playrho::d2::SetBeginContactListener ( World world,
ContactFunction  listener 
)
inlinenoexcept

Sets the begin-contact lister.

Note
This listener is called during calls to the Step(World&,const StepConf&) function for every contact that transitions from not previously touching, to touching in the step.
Parameters
worldThe world to set the listener for.
listenerFunction that the world is to call on these events.
See also
SetEndContactListener(World&, ContactFunction).

◆ SetBody() [1/2]

◆ SetBody() [2/2]

void playrho::d2::SetBody ( World world,
BodyID  id,
const Body body 
)
inline

Sets the state of the identified body.

Parameters
worldThe world containing the identified body whose state is to be set.
idIdentifier of the body whose state is to be set.
bodyNew state of the identified body.
Exceptions
std::out_of_rangeif id is out of range, or if the given body references any shape identifiers that are out of range.
InvalidArgumentif the specified ID was destroyed.
Postcondition
On success: GetBody(const World&, BodyID) for world and id returns the value of body .
See also
GetBody(const World&, BodyID), GetBodyRange, GetShapeRange.

◆ SetContact() [1/2]

void playrho::d2::SetContact ( AabbTreeWorld world,
ContactID  id,
Contact  value 
)

Sets the identified contact's state.

Note
The new state:
  • Is not allowed to change the bodies, shapes, or children identified.
  • Is not allowed to change whether the contact is awake.
  • Is not allowed to change whether the contact is impenetrable.
  • Is not allowed to change whether the contact is for a sensor.
  • Is not allowed to change the TOI of the contact.
  • Is not allowed to change the TOI count of the contact.
Parameters
worldThe world of the contact whose state is to be set.
idIdentifier of the contact whose state is to be set.
valueValue the contact is to be set to.
Exceptions
std::out_of_rangeIf given an invalid contact identifier or an invalid identifier in the new contact value.
InvalidArgumentif the identifier is to a freed contact or if the new state is not allowable.
See also
GetContact, GetContactRange.
Examples
World.cpp, and WorldContact.cpp.

Referenced by playrho::d2::detail::WorldModel< T >::SetContact_(), playrho::d2::World::SetEnabled(), playrho::d2::World::SetFriction(), playrho::d2::World::SetRestitution(), playrho::d2::World::SetTangentSpeed(), and playrho::d2::World::UnsetEnabled().

◆ SetContact() [2/2]

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

Sets the identified contact's state.

Parameters
worldThe world of the contact whose state is to be set.
idIdentifier of the contact whose state is to be set.
valueValue the contact is to be set to. The new state: is not allowed to change whether the contact is awake, is not allowed to change whether the contact is impenetrable, is not allowed to change whether the contact is for a sensor, is not allowed to change the TOI of the contact, is not allowed to change the TOI count of the contact. Otherwise, this function will throw an InvalidArgument exception and not change anything.
Exceptions
std::out_of_rangeIf given an out of range contact identifier or the new contact value references an out of range identifier.
InvalidArgumentif the identifier is to a freed contact or if the new state is not allowable.
See also
GetContact, GetContactRange.

◆ SetDensity() [1/2]

void playrho::d2::SetDensity ( Shape shape,
NonNegative< AreaDensity value 
)

Sets the density of the given shape.

See also
GetDensity.
Examples
WorldShape.cpp.

Referenced by playrho::d2::World::SetDensity().

◆ SetDensity() [2/2]

void playrho::d2::SetDensity ( World world,
ShapeID  id,
NonNegative< AreaDensity value 
)

Sets the density of this shape.

Exceptions
std::out_of_rangeIf given an invalid identifier.

◆ SetDestroyed()

constexpr void playrho::d2::SetDestroyed ( Body body)
constexprnoexcept

Sets the destroyed property of the given body.

Note
This is only meaningfully used by the world implementation.
Examples
Body.cpp.

◆ SetDetachListener()

void playrho::d2::SetDetachListener ( World world,
BodyShapeFunction  listener 
)
inlinenoexcept

Sets the detach listener for shapes detaching from bodies.

Note
This listener is called on Destroy(World&,BodyID) for every shape associated with that identified body.
Parameters
worldThe world to set the listener for.
listenerFunction that the world is to call on these events.
See also
Destroy(World&,BodyID).

◆ SetEnabled() [1/5]

void SetEnabled ( Body body)
inlinenoexcept

Sets the enabled state.

See also
IsEnabled(const Body&), UnsetEnabled(Body&).
Examples
WorldBody.cpp, and WorldContact.cpp.

Referenced by playrho::d2::World::SetEnabled().

◆ SetEnabled() [2/5]

void SetEnabled ( Body body,
bool  value 
)
inlinenoexcept

Sets the enabled state to the given value.

See also
IsEnabled(const Body&), SetEnabled(Body&), UnsetEnabled(Body&).

◆ SetEnabled() [3/5]

void playrho::d2::SetEnabled ( World world,
BodyID  id,
bool  value 
)

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() [4/5]

void playrho::d2::SetEnabled ( World world,
ContactID  id 
)

Sets the enabled status of the identified contact.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.

◆ SetEnabled() [5/5]

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

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).

◆ SetEndContactListener()

void playrho::d2::SetEndContactListener ( World world,
ContactFunction  listener 
)
inlinenoexcept

Sets the end-contact lister.

Note
This listener is called during calls to the Step(World&,const StepConf&) function for every contact that transitions from previously touching, to no longer touching in the step.
Parameters
worldThe world to set the listener for.
listenerFunction that the world is to call on these events.
See also
SetBeginContactListener(World&, ContactFunction).

◆ SetFilter()

void playrho::d2::SetFilter ( Shape shape,
Filter  value 
)

Sets the filter value for the given shape.

See also
GetFilter(const Shape& shape).

Referenced by playrho::d2::World::SetFilterData().

◆ SetFilterData()

void playrho::d2::SetFilterData ( World world,
ShapeID  id,
const Filter filter 
)

Convenience function for setting 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 identifier.
See also
GetFilterData.
Examples
World.cpp, and WorldShape.cpp.

◆ SetFixedRotation() [1/2]

void SetFixedRotation ( Body body,
bool  value 
)
inline

Sets this body to have fixed rotation.

Note
This causes the mass to be reset.
See also
IsFixedRotation(const Body&).
Examples
WorldBody.cpp.

Referenced by playrho::d2::World::SetFixedRotation().

◆ SetFixedRotation() [2/2]

void playrho::d2::SetFixedRotation ( World world,
BodyID  id,
bool  value 
)

Sets this body to have fixed rotation.

Exceptions
WrongStateif this function is called while the world is locked.
std::out_of_rangeIf given an invalid body identifier.
Note
This also causess the mass data to be reset.
See also
IsFixedRotation.

◆ SetForce()

void playrho::d2::SetForce ( World world,
BodyID  id,
const Force2 force,
const Length2 point 
)

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

Exceptions
WrongStateif this function is called while the world is locked.
std::out_of_rangeIf given an invalid body identifier.
Examples
WorldBody.cpp.

◆ SetFrequency() [1/2]

void playrho::d2::SetFrequency ( Joint object,
Frequency  value 
)

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

Exceptions
std::invalid_argumentIf not supported for the given joint's type.

◆ SetFrequency() [2/2]

void playrho::d2::SetFrequency ( World world,
JointID  id,
Frequency  value 
)

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

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

◆ SetFriction() [1/3]

void playrho::d2::SetFriction ( Shape shape,
NonNegative< Real value 
)

◆ SetFriction() [2/3]

void playrho::d2::SetFriction ( World world,
ContactID  id,
NonNegative< Real friction 
)

Sets the friction value for the identified contact.

Note
Overrides the default friction mixture. You can call this in "pre-solve" listeners. This value persists until set or reset.
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.
Postcondition
GetFriction(world, id) returns the value set.
Exceptions
std::out_of_rangeIf given an invalid contact identifier.
See also
GetFriction(const World&, ContactID).

◆ SetFriction() [3/3]

void playrho::d2::SetFriction ( World world,
ShapeID  id,
NonNegative< Real value 
)

Convenience function for setting the coefficient of friction of the specified shape.

Exceptions
std::out_of_rangeIf given an invalid identifier.
See also
GetFriction.

◆ SetImpenetrable() [1/3]

void SetImpenetrable ( Body body)
inlinenoexcept

Sets the impenetrable status of this body.

Sets whether or not this body should be treated like a bullet for continuous collision detection.

See also
IsImpenetrable(const Body&), UnsetImpenetrable(Body&).
Examples
World.cpp, and WorldContact.cpp.

Referenced by playrho::d2::World::SetImpenetrable().

◆ SetImpenetrable() [2/3]

void playrho::d2::SetImpenetrable ( World world,
BodyID  id 
)

Sets the impenetrable status of the identified body.

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

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

◆ SetImpenetrable() [3/3]

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

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

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

◆ SetJoint() [1/3]

void playrho::d2::SetJoint ( AabbTreeWorld world,
JointID  id,
Joint  def 
)

◆ SetJoint() [2/3]

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

Sets the value of the identified joint.

Exceptions
WrongStateif this function is called while the world is locked.
std::out_of_rangeIf given an out of range joint identifier.
See also
GetJointRange.

◆ SetJoint() [3/3]

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

Sets a joint's value from a configuration.

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

Exceptions
WrongStateif this function is called while the world is locked.
std::out_of_rangeIf given an out of range joint identifier.
See also
GetJointRange.

◆ SetJointDestructionListener() [1/2]

void playrho::d2::SetJointDestructionListener ( AabbTreeWorld world,
JointFunction  listener 
)
inlinenoexcept

Register a destruction listener for joints.

Note
This listener is called on Clear() for every joint. It's also called on Destroy(BodyID) for every joint associated with the identified body.
See also
Clear, Destroy(BodyID).
Examples
World.cpp.

Referenced by playrho::d2::detail::WorldModel< T >::SetJointDestructionListener_().

◆ SetJointDestructionListener() [2/2]

void playrho::d2::SetJointDestructionListener ( World world,
JointFunction  listener 
)
inlinenoexcept

Sets the destruction listener for joints.

Note
This listener is called on Clear(World&) for every joint. It's also called on Destroy(BodyID) for every joint associated with the identified body.
Parameters
worldThe world to set the listener for.
listenerFunction that the world is to call on these events.
See also
Clear(World&), Destroy(BodyID).

◆ SetLinearDamping() [1/2]

void SetLinearDamping ( Body body,
NonNegative< Frequency value 
)
inlinenoexcept

Sets the linear damping of the body.

See also
GetLinearDamping(const Body& body).
Examples
Body.cpp, and World.cpp.

Referenced by playrho::d2::World::SetLinearDamping().

◆ SetLinearDamping() [2/2]

void playrho::d2::SetLinearDamping ( World world,
BodyID  id,
NonNegative< Frequency linearDamping 
)

Sets the linear damping of the body.

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

◆ SetLinearLimits()

void playrho::d2::SetLinearLimits ( Joint object,
Length  lower,
Length  upper 
)

Sets the joint limits.

Exceptions
std::invalid_argumentIf not supported for the given joint's type.
Examples
Joint.cpp, and PrismaticJoint.cpp.

◆ SetLinearOffset() [1/2]

void playrho::d2::SetLinearOffset ( Joint object,
const Length2 value 
)

Sets the linear offset property of the specified joint if its type has one.

Exceptions
std::invalid_argumentIf not supported for the given joint's type.
Examples
MotorJoint.cpp, and PrismaticJoint.cpp.

Referenced by playrho::d2::World::SetLinearOffset().

◆ SetLinearOffset() [2/2]

void playrho::d2::SetLinearOffset ( World world,
JointID  id,
const Length2 value 
)

Sets the target linear offset, in frame A.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ SetLocation() [1/2]

void playrho::d2::SetLocation ( Body body,
const Length2 value 
)

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
bodyThe body to update.
valueValid world location of the body's local origin.
See also
GetLocation(const Body& body).
Examples
World.cpp, and WorldBody.cpp.

Referenced by playrho::d2::World::SetLocation().

◆ SetLocation() [2/2]

void playrho::d2::SetLocation ( World world,
BodyID  id,
const Length2 value 
)

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.
Exceptions
WrongStateif this function is called while the world is locked.
std::out_of_rangeIf given an invalid body identifier.
See also
GetLocation(const World& world, BodyID id).

◆ SetManifold() [1/2]

void playrho::d2::SetManifold ( AabbTreeWorld world,
ContactID  id,
const Manifold value 
)

Sets the identified manifold.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.
See also
GetManifold, GetContactRange.
Examples
World.cpp.

Referenced by playrho::d2::detail::WorldModel< T >::SetManifold_().

◆ SetManifold() [2/2]

void playrho::d2::SetManifold ( World world,
ContactID  id,
const Manifold value 
)
inline

Sets the identified manifold's state.

Note
There is a manifold for every contact and vice-versa.
Parameters
worldThe world of the manifold whose state is to be set.
idIdentifier of the manifold whose state is to be set.
valueValue the manifold is to be set to. The new state: TODO: is not allowed to change whether the contact is awake, TODO: is not allowed to change whether the contact is impenetrable. Otherwise, throws InvalidArgument exception and doesn't change anything.
Exceptions
std::out_of_rangeIf given an out of range contact identifier or the new manifold value references an out of range identifier.
InvalidArgumentif the identifier is to a freed contact or if the new state is not allowable.
See also
GetManifold, GetContactRange.

◆ SetMassData()

void playrho::d2::SetMassData ( World world,
BodyID  id,
const MassData massData 
)

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
WrongStateif this function is called while the world is locked.
std::out_of_rangeIf given an invalid body identifier.
Examples
WorldBody.cpp.

Referenced by playrho::d2::World::ResetMassData().

◆ SetMaxMotorForce()

void playrho::d2::SetMaxMotorForce ( Joint object,
Force  value 
)

Sets the given joint's max motor force if its type supports that.

Exceptions
std::invalid_argumentIf not supported for the given joint's type.
Examples
Joint.cpp, and PrismaticJoint.cpp.

◆ SetMaxMotorTorque() [1/2]

void playrho::d2::SetMaxMotorTorque ( Joint object,
Torque  value 
)

Sets the given joint's max motor torque if its type supports that.

Exceptions
std::invalid_argumentIf not supported for the given joint's type.
Examples
Joint.cpp, RevoluteJoint.cpp, and WheelJoint.cpp.

Referenced by playrho::d2::World::SetMaxMotorTorque().

◆ SetMaxMotorTorque() [2/2]

void playrho::d2::SetMaxMotorTorque ( World world,
JointID  id,
Torque  value 
)

Sets the maximum motor torque.

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

◆ SetMotorSpeed() [1/2]

void playrho::d2::SetMotorSpeed ( Joint object,
AngularVelocity  value 
)

Sets the given joint's motor speed if its type supports that.

Exceptions
std::invalid_argumentIf not supported for the given joint's type.
Examples
DistanceJoint.cpp, FrictionJoint.cpp, Joint.cpp, PrismaticJoint.cpp, RevoluteJoint.cpp, and WheelJoint.cpp.

Referenced by playrho::d2::World::SetMotorSpeed().

◆ SetMotorSpeed() [2/2]

void playrho::d2::SetMotorSpeed ( World world,
JointID  id,
AngularVelocity  value 
)

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

Exceptions
WrongStateif this function is called while the world is locked.
std::out_of_rangeIf given an invalid joint identifier.
See also
GetMotorSpeed(const World& world, JointID id)

◆ SetPostSolveContactListener()

void playrho::d2::SetPostSolveContactListener ( World world,
ContactImpulsesFunction  listener 
)
inlinenoexcept

Sets the post-solve-contact lister.

Note
This listener is called during calls to the Step(World&,const StepConf&) function for every contact that was "solved" during regular processing or TOI processing (or both).
Parameters
worldThe world to set the listener for.
listenerFunction that the world is to call on these events.
See also
SetPreSolveContactListener(World&, ContactManifoldFunction).

◆ SetPreSolveContactListener()

void playrho::d2::SetPreSolveContactListener ( World world,
ContactManifoldFunction  listener 
)
inlinenoexcept

Sets the pre-solve-contact lister.

Note
This listener is called during calls to the Step(World&,const StepConf&) function for every non-sensor contact that is touching.
Parameters
worldThe world to set the listener for.
listenerFunction that the world is to call on these events.
See also
SetPostSolveContactListener(World&, ContactImpulsesFunction).

◆ SetRestitution() [1/3]

void playrho::d2::SetRestitution ( Shape shape,
Real  value 
)

Sets the coefficient of restitution value of the given shape.

See also
GetRestitution(const Shape& shape).
Examples
WorldContact.cpp, and WorldShape.cpp.

Referenced by playrho::d2::World::ResetRestitution(), and playrho::d2::World::SetRestitution().

◆ SetRestitution() [2/3]

void playrho::d2::SetRestitution ( World world,
ContactID  id,
Real  restitution 
)

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.

◆ SetRestitution() [3/3]

void playrho::d2::SetRestitution ( World world,
ShapeID  id,
Real  value 
)

Sets the coefficient of restitution of the specified shape.

Exceptions
std::out_of_rangeIf given an invalid identifier.

◆ SetSensor() [1/2]

void playrho::d2::SetSensor ( Shape shape,
bool  value 
)

Sets whether or not the given shape is a sensor.

See also
IsSensor(const Shape& shape).
Examples
World.cpp, WorldContact.cpp, and WorldShape.cpp.

Referenced by playrho::d2::World::SetSensor().

◆ SetSensor() [2/2]

void playrho::d2::SetSensor ( World world,
ShapeID  id,
bool  value 
)

Convenience function for setting whether the shape is a sensor or not.

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

◆ SetShape() [1/2]

void playrho::d2::SetShape ( AabbTreeWorld world,
ShapeID  id,
Shape  def 
)

Sets the value of the identified shape.

Warning
This function is locked during callbacks.
Note
This function does not reset the mass data of any effected bodies.
Exceptions
WrongStateif this function is called while the world is locked.
std::out_of_rangeIf given an invalid identifier.
InvalidArgumentif the specified ID was destroyed.
See also
CreateShape, Destroy(ShapeID id).
Examples
World.cpp.

Referenced by playrho::d2::World::Rotate(), playrho::d2::World::Scale(), playrho::d2::World::SetDensity(), playrho::d2::World::SetFilterData(), playrho::d2::World::SetFriction(), playrho::d2::World::SetRestitution(), playrho::d2::World::SetSensor(), playrho::d2::detail::WorldModel< T >::SetShape_(), and playrho::d2::World::Translate().

◆ SetShape() [2/2]

void playrho::d2::SetShape ( World world,
ShapeID  id,
const Shape def 
)
inline

Sets the identified shape to the new value.

Exceptions
std::out_of_rangeIf given an out of range shape identifier.
See also
CreateShape, GetShapeRange.

◆ SetShapeDestructionListener() [1/2]

void playrho::d2::SetShapeDestructionListener ( AabbTreeWorld world,
ShapeFunction  listener 
)
inlinenoexcept

Registers a destruction listener for shapes.

Note
This listener is called on Clear(AabbTreeWorld&) for every shape.
See also
Clear(AabbTreeWorld&).
Examples
World.cpp.

Referenced by playrho::d2::detail::WorldModel< T >::SetShapeDestructionListener_().

◆ SetShapeDestructionListener() [2/2]

void playrho::d2::SetShapeDestructionListener ( World world,
ShapeFunction  listener 
)
inlinenoexcept

Sets the destruction listener for shapes.

Note
This listener is called on Clear(World&) for every shape.
Parameters
worldThe world to set the listener for.
listenerFunction that the world is to call on these events.
See also
Clear(World&).

◆ SetSleepingAllowed() [1/2]

void SetSleepingAllowed ( Body body,
bool  value 
)
inlinenoexcept

You can disable sleeping on this body. If you disable sleeping, the body will be woken.

See also
IsSleepingAllowed(const Body&).
Examples
World.cpp.

Referenced by playrho::d2::World::SetSleepingAllowed().

◆ SetSleepingAllowed() [2/2]

void playrho::d2::SetSleepingAllowed ( World world,
BodyID  id,
bool  value 
)

Sets whether the identified body is allowed to sleep.

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

◆ SetSubStepping() [1/2]

void playrho::d2::SetSubStepping ( AabbTreeWorld world,
bool  flag 
)
inlinenoexcept

Enables/disables single stepped continuous physics.

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

Referenced by playrho::d2::detail::WorldModel< T >::SetSubStepping_().

◆ SetSubStepping() [2/2]

void playrho::d2::SetSubStepping ( World world,
bool  flag 
)
inlinenoexcept

Enables/disables single stepped continuous physics.

Note
This is not normally used. Enabling sub-stepping is meant for testing.
Parameters
worldThe world to set whether or not to do sub-stepping for.
flagtrue to enable sub-stepping, false to disable it.
Postcondition
The GetSubStepping() function will return the value this function was called with.
See also
IsStepComplete, GetSubStepping.

◆ SetSweep()

void SetSweep ( Body body,
const Sweep value 
)
inlinenoexcept

◆ SetTangentSpeed()

void playrho::d2::SetTangentSpeed ( World world,
ContactID  id,
LinearVelocity  value 
)

Sets the desired tangent speed for a conveyor belt behavior.

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

Referenced by playrho::d2::World::SetTangentSpeed().

◆ SetTarget() [1/2]

void playrho::d2::SetTarget ( Joint object,
const Length2 value 
)

Sets the given joint's target property if it has one.

Exceptions
std::invalid_argumentIf not supported for the given joint's type.
Examples
PrismaticJoint.cpp, and World.cpp.

Referenced by playrho::d2::World::SetTarget().

◆ SetTarget() [2/2]

void playrho::d2::SetTarget ( World world,
JointID  id,
const Length2 value 
)

Sets the target point.

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

◆ SetTorque()

void playrho::d2::SetTorque ( World world,
BodyID  id,
Torque  torque 
)

Sets the given amount of torque to the given body.

Exceptions
WrongStateif this function is called while the world is locked.
std::out_of_rangeIf given an invalid body identifier.
Examples
WorldBody.cpp.

◆ SetTransform()

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

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.
angleValid world rotation.
Exceptions
WrongStateif this function is called while the world is locked.
std::out_of_rangeIf given an invalid body identifier.
Examples
WorldBody.cpp.

Referenced by playrho::d2::World::RotateAboutWorldPoint().

◆ SetTransformation() [1/2]

void playrho::d2::SetTransformation ( Body body,
const Transformation value 
)
noexcept

Sets the body's transformation.

Note
This sets the sweep to the new transformation.
Postcondition
GetTransformation(const Body& body) will return the value set.
GetPosition1(const Body& body) will return a position equivalent to value given.
See also
GetTransformation(const Body& body), GetPosition1(const Body& body).
Examples
Body.cpp, and WorldBody.cpp.

Referenced by playrho::d2::Body::SetLocation(), playrho::d2::World::SetTransform(), and playrho::d2::World::SetTransformation().

◆ SetTransformation() [2/2]

void playrho::d2::SetTransformation ( World world,
BodyID  id,
const Transformation value 
)

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
WrongStateif this function is called while the world is locked.
std::out_of_rangeIf given an invalid body identifier.
See also
GetTransformation(const World& world, BodyID id).

◆ SetType() [1/2]

void SetType ( Body body,
BodyType  value 
)
inlinenoexcept

Sets the type of this body.

See also
GetType(const Body&).
Examples
World.cpp, and WorldBody.cpp.

Referenced by playrho::d2::World::SetType().

◆ SetType() [2/2]

void playrho::d2::SetType ( World world,
BodyID  id,
BodyType  value,
bool  resetMassData = true 
)

Sets the type of the given body.

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

◆ SetVelocity() [1/6]

void SetVelocity ( Body body,
AngularVelocity  value 
)
inlinenoexcept

Sets the angular velocity.

Parameters
bodyBody to set the angular velocity of.
valuethe new angular velocity.
See also
GetAngularVelocity(const Body& body).

◆ SetVelocity() [2/6]

void SetVelocity ( Body body,
const LinearVelocity2 value 
)
inlinenoexcept

Sets the linear velocity of the center of mass.

Parameters
bodyBody to set the linear velocity of.
valuethe new linear velocity of the center of mass.
See also
GetLinearVelocity(const Body& body).

◆ SetVelocity() [3/6]

void SetVelocity ( Body body,
const Velocity value 
)
inlinenoexcept

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

Note
This function does nothing if this body is not speedable.
A non-zero velocity will awaken this body.
See also
GetVelocity(const Body& body), SetAwake, SetUnderActiveTime.
Examples
World.cpp, and WorldBody.cpp.

Referenced by playrho::d2::World::SetVelocity().

◆ SetVelocity() [4/6]

void playrho::d2::SetVelocity ( World world,
BodyID  id,
AngularVelocity  value 
)

Sets the velocity of the identified body.

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

◆ SetVelocity() [5/6]

void playrho::d2::SetVelocity ( World world,
BodyID  id,
const LinearVelocity2 value 
)

Sets the velocity of the identified body.

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

◆ SetVelocity() [6/6]

void playrho::d2::SetVelocity ( World world,
BodyID  id,
const Velocity value 
)

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

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

◆ SetVertexRadius()

void playrho::d2::SetVertexRadius ( Shape shape,
ChildCounter  idx,
NonNegative< Length value 
)

Sets the vertex radius of the indexed child of the given shape.

Exceptions
InvalidArgumentif the vertex radius cannot be set to the specified value.
See also
GetVertexRadius(const Shape& shape, ChildCounter idx).

◆ ShiftOrigin() [1/4]

void playrho::d2::ShiftOrigin ( AabbTreeWorld world,
const 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
worldThe world whose origin should be shifted.
newOriginthe new origin with respect to the old origin
Exceptions
WrongStateif this function is called while the world is locked.
Examples
DistanceJoint.cpp, FrictionJoint.cpp, GearJoint.cpp, MotorJoint.cpp, PrismaticJoint.cpp, PulleyJoint.cpp, RevoluteJoint.cpp, RopeJoint.cpp, TargetJoint.cpp, WeldJoint.cpp, WheelJoint.cpp, and World.cpp.

Referenced by playrho::d2::World::ShiftOrigin(), playrho::d2::detail::WorldModel< T >::ShiftOrigin_(), and playrho::d2::detail::JointModel< T >::ShiftOrigin_().

◆ ShiftOrigin() [2/4]

bool playrho::d2::ShiftOrigin ( Joint object,
const Length2 value 
)
noexcept

Shifts the origin for any points stored in world coordinates.

Returns
true if shift done, false otherwise.

◆ ShiftOrigin() [3/4]

void playrho::d2::ShiftOrigin ( World world,
const Length2 newOrigin 
)
inline

Shifts the origin of the specified world.

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 is to be shifted.
newOriginthe new origin with respect to the old origin
Exceptions
WrongStateif this function is called while the world is locked.

◆ ShiftOrigin() [4/4]

bool playrho::d2::ShiftOrigin ( World world,
JointID  id,
const Length2 value 
)

Shifts the origin of the identified joint.

Note
This only effects joints having points in world coordinates.
Exceptions
WrongStateif this function is called while the world is locked.
std::out_of_rangeIf given an invalid joint identifier.

◆ ShouldCollide()

bool ShouldCollide ( const Shape a,
const Shape b 
)
inlinenoexcept

Whether contact calculations should be performed between the two instances.

Returns
true if contact calculations should be performed between these two instances; false otherwise.

Referenced by playrho::d2::Shape::ShouldCollide().

◆ size()

◆ SolvePosition() [1/12]

bool playrho::d2::SolvePosition ( const DistanceJointConf object,
const Span< BodyConstraint > &  bodies,
const ConstraintSolverConf conf 
)

Solves the position constraint.

Parameters
objectConfiguration object. bodyA and bodyB must index bodies within the given bodies container or be the special body ID value of InvalidBodyID.
bodiesContainer of body constraints.
confConstraint solver configuration.
Exceptions
std::out_of_rangeIf the given object's bodyA or bodyB values are not InvalidBodyID and are not indices within range of the given bodies container.
Returns
true if the position errors are within tolerance.
Examples
DistanceJoint.cpp, FrictionJoint.cpp, GearJoint.cpp, MotorJoint.cpp, PrismaticJoint.cpp, PulleyJoint.cpp, RevoluteJoint.cpp, RopeJoint.cpp, TargetJoint.cpp, WeldJoint.cpp, and WheelJoint.cpp.

Referenced by playrho::d2::detail::JointModel< T >::SolvePosition_().

◆ SolvePosition() [2/12]

bool playrho::d2::SolvePosition ( const FrictionJointConf object,
const Span< BodyConstraint > &  bodies,
const ConstraintSolverConf conf 
)

Solves the position constraint.

Note
This is a no-op and always returns true.
Returns
true.

◆ SolvePosition() [3/12]

bool playrho::d2::SolvePosition ( const GearJointConf object,
const Span< BodyConstraint > &  bodies,
const ConstraintSolverConf conf 
)

Solves the position constraint.

Parameters
objectConfiguration object. bodyA and bodyB must index bodies within the given bodies container or be the special body ID value of InvalidBodyID.
bodiesContainer of body constraints.
confConstraint solver configuration.
Exceptions
std::out_of_rangeIf the given object's bodyA or bodyB values are not InvalidBodyID and are not indices within range of the given bodies container.
Returns
true if the position errors are within tolerance.

◆ SolvePosition() [4/12]

bool playrho::d2::SolvePosition ( const Joint object,
const Span< BodyConstraint > &  bodies,
const ConstraintSolverConf conf 
)

Solves the position constraint.

Returns
true if the position errors are within tolerance.

◆ SolvePosition() [5/12]

bool playrho::d2::SolvePosition ( const MotorJointConf object,
const Span< BodyConstraint > &  bodies,
const ConstraintSolverConf conf 
)

Solves the position constraint.

Note
This is a no-op and always returns true.
Returns
true.

◆ SolvePosition() [6/12]

bool playrho::d2::SolvePosition ( const PrismaticJointConf object,
const Span< BodyConstraint > &  bodies,
const ConstraintSolverConf conf 
)

Solves the position constraint.

Parameters
objectConfiguration object. bodyA and bodyB must index bodies within the given bodies container or be the special body ID value of InvalidBodyID.
bodiesContainer of body constraints.
confConstraint solver configuration.
Exceptions
std::out_of_rangeIf the given object's bodyA or bodyB values are not InvalidBodyID and are not indices within range of the given bodies container.
Returns
true if the position errors are within tolerance.

◆ SolvePosition() [7/12]

bool playrho::d2::SolvePosition ( const PulleyJointConf object,
const Span< BodyConstraint > &  bodies,
const ConstraintSolverConf conf 
)

Solves the position constraint.

Parameters
objectConfiguration object. bodyA and bodyB must index bodies within the given bodies container or be the special body ID value of InvalidBodyID.
bodiesContainer of body constraints.
confConstraint solver configuration.
Exceptions
std::out_of_rangeIf the given object's bodyA or bodyB values are not InvalidBodyID and are not indices within range of the given bodies container.
Returns
true if the position errors are within tolerance.

◆ SolvePosition() [8/12]

bool playrho::d2::SolvePosition ( const RevoluteJointConf object,
const Span< BodyConstraint > &  bodies,
const ConstraintSolverConf conf 
)

Solves the position constraint.

Parameters
objectConfiguration object. bodyA and bodyB must index bodies within the given bodies container or be the special body ID value of InvalidBodyID.
bodiesContainer of body constraints.
confConstraint solver configuration.
Exceptions
std::out_of_rangeIf the given object's bodyA or bodyB values are not InvalidBodyID and are not indices within range of the given bodies container.
Returns
true if the position errors are within tolerance.

◆ SolvePosition() [9/12]

bool playrho::d2::SolvePosition ( const RopeJointConf object,
const Span< BodyConstraint > &  bodies,
const ConstraintSolverConf conf 
)

Solves the position constraint.

Parameters
objectConfiguration object. bodyA and bodyB must index bodies within the given bodies container or be the special body ID value of InvalidBodyID.
bodiesContainer of body constraints.
confConstraint solver configuration.
Exceptions
std::out_of_rangeIf the given object's bodyA or bodyB values are not InvalidBodyID and are not indices within range of the given bodies container.
Returns
true if the position errors are within tolerance.

◆ SolvePosition() [10/12]

bool playrho::d2::SolvePosition ( const TargetJointConf object,
const Span< BodyConstraint > &  bodies,
const ConstraintSolverConf conf 
)

Solves the position constraint.

Note
This is a no-op and always returns true.
Returns
true.

◆ SolvePosition() [11/12]

bool playrho::d2::SolvePosition ( const WeldJointConf object,
const Span< BodyConstraint > &  bodies,
const ConstraintSolverConf conf 
)

Solves the position constraint.

Parameters
objectConfiguration object. bodyA and bodyB must index bodies within the given bodies container or be the special body ID value of InvalidBodyID.
bodiesContainer of body constraints.
confConstraint solver configuration.
Exceptions
std::out_of_rangeIf the given object's bodyA or bodyB values are not InvalidBodyID and are not indices within range of the given bodies container.
Returns
true if the position errors are within tolerance.

◆ SolvePosition() [12/12]

bool playrho::d2::SolvePosition ( const WheelJointConf object,
const Span< BodyConstraint > &  bodies,
const ConstraintSolverConf conf 
)

Solves the position constraint.

Parameters
objectConfiguration object. bodyA and bodyB must index bodies within the given bodies container or be the special body ID value of InvalidBodyID.
bodiesContainer of body constraints.
confConstraint solver configuration.
Exceptions
std::out_of_rangeIf the given object's bodyA or bodyB values are not InvalidBodyID and are not indices within range of the given bodies container.
Returns
true if the position errors are within tolerance.

◆ SolveVelocity() [1/12]

bool playrho::d2::SolveVelocity ( DistanceJointConf object,
const Span< BodyConstraint > &  bodies,
const StepConf step 
)

Solves velocity constraint.

Precondition
InitVelocity has been called.
Parameters
objectConfiguration object. bodyA and bodyB must index bodies within the given bodies container or be the special body ID value of InvalidBodyID.
bodiesContainer of body constraints.
stepConfiguration for the step.
Exceptions
std::out_of_rangeIf the given object's bodyA or bodyB values are not InvalidBodyID and are not indices within range of the given bodies container.
See also
InitVelocity.
Returns
true if velocity is "solved", false otherwise.
Examples
DistanceJoint.cpp, FrictionJoint.cpp, GearJoint.cpp, MotorJoint.cpp, PrismaticJoint.cpp, PulleyJoint.cpp, RevoluteJoint.cpp, RopeJoint.cpp, TargetJoint.cpp, WeldJoint.cpp, and WheelJoint.cpp.

Referenced by playrho::d2::detail::JointModel< T >::SolveVelocity_().

◆ SolveVelocity() [2/12]

bool playrho::d2::SolveVelocity ( FrictionJointConf object,
const Span< BodyConstraint > &  bodies,
const StepConf step 
)

Solves velocity constraint.

Precondition
InitVelocity has been called.
Parameters
objectConfiguration object. bodyA and bodyB must index bodies within the given bodies container or be the special body ID value of InvalidBodyID.
bodiesContainer of body constraints.
stepConfiguration for the step.
Exceptions
std::out_of_rangeIf the given object's bodyA or bodyB values are not InvalidBodyID and are not indices within range of the given bodies container.
See also
InitVelocity.
Returns
true if velocity is "solved", false otherwise.

◆ SolveVelocity() [3/12]

bool playrho::d2::SolveVelocity ( GearJointConf object,
const Span< BodyConstraint > &  bodies,
const StepConf step 
)

Solves velocity constraint.

Precondition
InitVelocity has been called.
Parameters
objectConfiguration object. bodyA and bodyB must index bodies within the given bodies container or be the special body ID value of InvalidBodyID.
bodiesContainer of body constraints.
stepConfiguration for the step.
Exceptions
std::out_of_rangeIf the given object's bodyA or bodyB values are not InvalidBodyID and are not indices within range of the given bodies container.
See also
InitVelocity.
Returns
true if velocity is "solved", false otherwise.

◆ SolveVelocity() [4/12]

bool playrho::d2::SolveVelocity ( Joint object,
const Span< BodyConstraint > &  bodies,
const StepConf step 
)

Solves velocity constraint.

Precondition
InitVelocity has been called.
See also
InitVelocity.
Returns
true if velocity is "solved", false otherwise.

◆ SolveVelocity() [5/12]

bool playrho::d2::SolveVelocity ( MotorJointConf object,
const Span< BodyConstraint > &  bodies,
const StepConf step 
)

Solves velocity constraint.

Precondition
InitVelocity has been called.
Parameters
objectConfiguration object. bodyA and bodyB must index bodies within the given bodies container or be the special body ID value of InvalidBodyID.
bodiesContainer of body constraints.
stepConfiguration for the step.
Exceptions
std::out_of_rangeIf the given object's bodyA or bodyB values are not InvalidBodyID and are not indices within range of the given bodies container.
See also
InitVelocity.
Returns
true if velocity is "solved", false otherwise.

◆ SolveVelocity() [6/12]

bool playrho::d2::SolveVelocity ( PrismaticJointConf object,
const Span< BodyConstraint > &  bodies,
const StepConf step 
)

Solves velocity constraint.

Precondition
InitVelocity has been called.
Parameters
objectConfiguration object. bodyA and bodyB must index bodies within the given bodies container or be the special body ID value of InvalidBodyID.
bodiesContainer of body constraints.
stepConfiguration for the step.
Exceptions
std::out_of_rangeIf the given object's bodyA or bodyB values are not InvalidBodyID and are not indices within range of the given bodies container.
See also
InitVelocity.
Returns
true if velocity is "solved", false otherwise.

◆ SolveVelocity() [7/12]

bool playrho::d2::SolveVelocity ( PulleyJointConf object,
const Span< BodyConstraint > &  bodies,
const StepConf step 
)

Solves velocity constraint.

Precondition
InitVelocity has been called.
Parameters
objectConfiguration object. bodyA and bodyB must index bodies within the given bodies container or be the special body ID value of InvalidBodyID.
bodiesContainer of body constraints.
stepConfiguration for the step.
Exceptions
std::out_of_rangeIf the given object's bodyA or bodyB values are not InvalidBodyID and are not indices within range of the given bodies container.
See also
InitVelocity.
Returns
true if velocity is "solved", false otherwise.

◆ SolveVelocity() [8/12]

bool playrho::d2::SolveVelocity ( RevoluteJointConf object,
const Span< BodyConstraint > &  bodies,
const StepConf step 
)

Solves velocity constraint.

Precondition
InitVelocity has been called.
Parameters
objectConfiguration object. bodyA and bodyB must index bodies within the given bodies container or be the special body ID value of InvalidBodyID.
bodiesContainer of body constraints.
stepConfiguration for the step.
Exceptions
std::out_of_rangeIf the given object's bodyA or bodyB values are not InvalidBodyID and are not indices within range of the given bodies container.
See also
InitVelocity.
Returns
true if velocity is "solved", false otherwise.

◆ SolveVelocity() [9/12]

bool playrho::d2::SolveVelocity ( RopeJointConf object,
const Span< BodyConstraint > &  bodies,
const StepConf step 
)

Solves velocity constraint.

Precondition
InitVelocity has been called.
Parameters
objectConfiguration object. bodyA and bodyB must index bodies within the given bodies container or be the special body ID value of InvalidBodyID.
bodiesContainer of body constraints.
stepConfiguration for the step.
Exceptions
std::out_of_rangeIf the given object's bodyA or bodyB values are not InvalidBodyID and are not indices within range of the given bodies container.
See also
InitVelocity.
Returns
true if velocity is "solved", false otherwise.

◆ SolveVelocity() [10/12]

bool playrho::d2::SolveVelocity ( TargetJointConf object,
const Span< BodyConstraint > &  bodies,
const StepConf step 
)

Solves velocity constraint.

Precondition
InitVelocity has been called.
Parameters
objectConfiguration object. bodyB must index a body within the given bodies container or be the special body ID value of InvalidBodyID.
bodiesContainer of body constraints.
stepConfiguration for the step.
Exceptions
std::out_of_rangeIf the given object's bodyB value is not InvalidBodyID and does not index within range of the given bodies container.
See also
InitVelocity.
Returns
true if velocity is "solved", false otherwise.

◆ SolveVelocity() [11/12]

bool playrho::d2::SolveVelocity ( WeldJointConf object,
const Span< BodyConstraint > &  bodies,
const StepConf step 
)

Solves velocity constraint.

Precondition
InitVelocity has been called.
Parameters
objectConfiguration object. bodyA and bodyB must index bodies within the given bodies container or be the special body ID value of InvalidBodyID.
bodiesContainer of body constraints.
stepConfiguration for the step.
Exceptions
std::out_of_rangeIf the given object's bodyA or bodyB values are not InvalidBodyID and are not indices within range of the given bodies container.
See also
InitVelocity.
Returns
true if velocity is "solved", false otherwise.

◆ SolveVelocity() [12/12]

bool playrho::d2::SolveVelocity ( WheelJointConf object,
const Span< BodyConstraint > &  bodies,
const StepConf step 
)

Solves velocity constraint.

Precondition
InitVelocity has been called.
Parameters
objectConfiguration object. bodyA and bodyB must index bodies within the given bodies container or be the special body ID value of InvalidBodyID.
bodiesContainer of body constraints.
stepConfiguration for the step.
Exceptions
std::out_of_rangeIf the given object's bodyA or bodyB values are not InvalidBodyID and are not indices within range of the given bodies container.
See also
InitVelocity.
Returns
true if velocity is "solved", false otherwise.

◆ Step() [1/3]

StepStats playrho::d2::Step ( AabbTreeWorld world,
const StepConf conf 
)

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
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 proxy handling being processed. No physics is performed.
If the given velocity and position iterations are zero, this function 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.
Parameters
worldThe world that is to be stepped.
confConfiguration for the simulation step.
Precondition
conf.linearSlop is significant enough compared to GetVertexRadiusInterval(const AabbTreeWorld& world).GetMax().
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.
The bodies for proxies queue will be empty.
The fixtures for proxies queue will be empty.
No contact in the world needs updating.
Returns
Statistics for the step.
Exceptions
WrongStateif this function is called while the world is locked.
See also
GetBodiesForProxies, GetFixturesForProxies.
Examples
DistanceJoint.cpp, FrictionJoint.cpp, GearJoint.cpp, HelloWorld.cpp, MotorJoint.cpp, PrismaticJoint.cpp, RevoluteJoint.cpp, RopeJoint.cpp, WeldJoint.cpp, WheelJoint.cpp, World.cpp, and WorldContact.cpp.

Referenced by playrho::d2::World::Step(), and playrho::d2::detail::WorldModel< T >::Step_().

◆ Step() [2/3]

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

Steps the given 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 not specified 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 function 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.
While this function is running, some listener functions could get called. Meanwhile some functions on World can only operate while the world is not in the middle of being updated by this function. Listeners can use the IsLocked(const World& world) function to detect whether they've been called in this case or not and then act accordingly.
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
worldThe world to simulate a step for.
confConfiguration for the simulation step.
Returns
Statistics for the step.
Exceptions
WrongStateif this function is called while the world is locked.
See also
IsLocked(const World&).

◆ Step() [3/3]

StepStats playrho::d2::Step ( World world,
Time  delta,
TimestepIters  velocityIterations = StepConf::DefaultRegVelocityIters,
TimestepIters  positionIterations = StepConf::DefaultRegPositionIters 
)

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 function 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.

◆ swap()

void playrho::d2::swap ( DynamicTree lhs,
DynamicTree rhs 
)
noexcept
Note
This satisfies the Swappable named requirement.
See also
https://en.cppreference.com/w/cpp/named_req/Swappable

Referenced by playrho::d2::DynamicTree::operator=(), and RayCast().

◆ TestOverlap()

Area playrho::d2::TestOverlap ( const DistanceProxy proxyA,
const Transformation xfA,
const DistanceProxy proxyB,
const Transformation xfB,
DistanceConf  conf = DistanceConf{} 
)

Determine if two generic shapes overlap.

Note
The returned touching state information typically agrees with that returned from the CollideShapes function. This is not always the case however especially when the separation or overlap distance is closer to zero.
Examples
Shape.cpp, and World.cpp.

Referenced by Query(), RayCast(), and playrho::d2::DynamicTree::TestOverlap().

◆ Transform() [1/2]

constexpr Length2 playrho::d2::Transform ( const Length2 v,
const Transformation xfm 
)
constexprnoexcept

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

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

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

Referenced by playrho::d2::DistanceProxy::ComputeAABB(), playrho::d2::World::GetAnchorA(), playrho::d2::World::GetAnchorB(), GetManifold(), playrho::d2::DistanceProxy::GetMaxSeparation(), playrho::d2::DistanceProxy::GetMaxSeparation4x4(), GetSeparationScenario(), playrho::d2::Body::GetWorldPoint(), playrho::d2::World::GetWorldPoint(), playrho::d2::DistanceProxy::RayCast(), playrho::d2::World::SetMassData(), playrho::d2::FrictionJointConf::SolveVelocity(), playrho::d2::MotorJointConf::SolveVelocity(), playrho::d2::TargetJointConf::SolveVelocity(), playrho::d2::WeldJointConf::SolveVelocity(), and playrho::d2::PolygonShapeConf::Transform().

◆ Transform() [2/2]

void Transform ( PolygonShapeConf arg,
const Mat22 m 
)
inline

Transforms the given polygon configuration's vertices by the given transformation matrix.

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

◆ Translate() [1/2]

void playrho::d2::Translate ( Shape shape,
const Length2 value 
)

Translates all of the given shape's vertices by the given amount.

Note
This may throw std::bad_alloc or any exception that's thrown by the constructor for the model's underlying data type.
Exceptions
std::bad_allocif there's a failure allocating storage.

◆ Translate() [2/2]

void playrho::d2::Translate ( World world,
ShapeID  id,
const Length2 value 
)

Translates all of the given shape's vertices by the given amount.

Note
This may throw std::bad_alloc or any exception that's thrown by the constructor for the model's underlying data type.
Exceptions
std::bad_allocif there's a failure allocating storage.
std::out_of_rangeIf given an invalid identifier.

◆ TypeCast() [1/12]

template<typename T >
T TypeCast ( const Joint value)
inline

Converts the given joint into its current configuration value.

Note
The design for this was based off the design of the C++17 std::any class and its associated std::any_cast function. The code for this is based off of the std::any implementation from the LLVM Project.
Exceptions
std::bad_castIf the given template parameter type isn't the type of this joint's configuration value.
See also
https://llvm.org/

◆ TypeCast() [2/12]

template<typename T >
std::add_pointer_t< std::add_const_t< T > > playrho::d2::TypeCast ( const Joint value)
inlinenoexcept

Converts the given joint into its current configuration value.

Note
The design for this was based off the design of the C++17 std::any class and its associated std::any_cast function. The code for this is based off of the std::any code from the LLVM Project.
See also
https://llvm.org/
Examples
DistanceJoint.cpp, Joint.cpp, Shape.cpp, and World.cpp.

◆ TypeCast() [3/12]

template<typename T >
T TypeCast ( const Shape value)
inline

Casts the specified instance into the template specified type.

Exceptions
std::bad_castIf the template specified type is not the type of data underlying the given instance.
See also
GetType(const Shape&)

◆ TypeCast() [4/12]

template<typename T >
std::add_pointer_t< std::add_const_t< T > > playrho::d2::TypeCast ( const Shape value)
noexcept

Converts the given shape into its current configuration value.

Note
The design for this was based off the design of the C++17 std::any class and its associated std::any_cast function. The code for this is based off of the std::any code from the LLVM Project.
See also
https://llvm.org/
GetType(const Shape&)

◆ TypeCast() [5/12]

template<typename T >
T TypeCast ( const World value)
inline

Converts the given joint into its current configuration value.

Note
The design for this was based off the design of the C++17 std::any class and its associated std::any_cast function. The code for this is based off of the std::any implementation from the LLVM Project.
Exceptions
std::bad_castIf the given template parameter type isn't the type of this joint's configuration value.
See also
https://llvm.org/

◆ TypeCast() [6/12]

template<typename T >
std::add_pointer_t< std::add_const_t< T > > playrho::d2::TypeCast ( const World value)
inlinenoexcept

Casts the given world into its current underlying configuration value.

Note
The design for this was based off the design of the C++17 std::any class and its associated std::any_cast function. The code for this is based off of the std::any code from the LLVM Project.
Template Parameters
Ttype to cast the underlying value of the given world to, if matching the actual type of the underlying value.
Parameters
valuePointer to the world whose underlying value, if it's type is the type of the template parameter, is to be returned.
See also
GetType(const World&).
https://llvm.org/

◆ TypeCast() [7/12]

template<typename T >
T TypeCast ( Joint &&  value)
inline

Converts the given joint into its current configuration value.

Note
The design for this was based off the design of the C++17 std::any class and its associated std::any_cast function. The code for this is based off of the std::any implementation from the LLVM Project.
See also
https://llvm.org/

◆ TypeCast() [8/12]

template<typename T >
T TypeCast ( Joint value)
inline

Converts the given joint into its current configuration value.

Note
The design for this was based off the design of the C++17 std::any class and its associated std::any_cast function. The code for this is based off of the std::any implementation from the LLVM Project.
See also
https://llvm.org/

◆ TypeCast() [9/12]

template<typename T >
std::add_pointer_t< T > playrho::d2::TypeCast ( Joint value)
inlinenoexcept

Converts the given joint into its current configuration value.

Note
The design for this was based off the design of the C++17 std::any class and its associated std::any_cast function. The code for this is based off of the std::any implementation from the LLVM Project.
See also
https://llvm.org/

◆ TypeCast() [10/12]

template<typename T >
T TypeCast ( World &&  value)
inline

Converts the given joint into its current configuration value.

Note
The design for this was based off the design of the C++17 std::any class and its associated std::any_cast function. The code for this is based off of the std::any implementation from the LLVM Project.
See also
https://llvm.org/

◆ TypeCast() [11/12]

template<typename T >
T TypeCast ( World value)
inline

Converts the given joint into its current configuration value.

Note
The design for this was based off the design of the C++17 std::any class and its associated std::any_cast function. The code for this is based off of the std::any implementation from the LLVM Project.
See also
https://llvm.org/

◆ TypeCast() [12/12]

template<typename T >
std::add_pointer_t< T > playrho::d2::TypeCast ( World value)
inlinenoexcept

Casts the given world into its current configuration value.

Note
The design for this was based off the design of the C++17 std::any class and its associated std::any_cast function. The code for this is based off of the std::any implementation from the LLVM Project.
Template Parameters
Ttype to cast the underlying value of the given world to, if matching the actual type of the underlying value.
Parameters
valuePointer to the world whose underlying value, if it's type is the type of the template parameter, is to be returned.
See also
GetType(const World&).
https://llvm.org/

◆ Unawaken()

bool Unawaken ( Body body)
inlinenoexcept

Puts the body to sleep if it's awake.

See also
Awaken(Body& body).

◆ UnsetAwake() [1/2]

void UnsetAwake ( Body body)
inlinenoexcept

Sets this body to asleep if sleeping is allowed.

If this body is allowed to sleep, this: sets the sleep state of the body to asleep, resets this body's under active time, and resets this body's velocity (linear and angular).

Postcondition
IsAwake(const Body&) function returns false.
This body's GetUnderActiveTime function returns zero.
This body's GetVelocity function returns zero linear and zero angular speed.
See also
IsAwake(const Body&), SetAwake(Body&).
Examples
RevoluteJoint.cpp, WorldBody.cpp, and WorldContact.cpp.

Referenced by playrho::d2::World::UnsetAwake().

◆ UnsetAwake() [2/2]

void playrho::d2::UnsetAwake ( World world,
BodyID  id 
)

Sleeps the identified body.

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

◆ UnsetDestroyed()

constexpr void playrho::d2::UnsetDestroyed ( Body body)
constexprnoexcept

Unsets the destroyed property of the given body.

Note
This is only meaningfully used by the world implementation.
Examples
Body.cpp.

◆ UnsetEnabled() [1/2]

void UnsetEnabled ( Body body)
inlinenoexcept

◆ UnsetEnabled() [2/2]

void playrho::d2::UnsetEnabled ( World world,
ContactID  id 
)

Unsets the enabled status of the identified contact.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.

◆ UnsetImpenetrable() [1/2]

void UnsetImpenetrable ( Body body)
inlinenoexcept

Unsets the impenetrable status of this body.

Sets whether or not this body should be treated like a bullet for continuous collision detection.

See also
IsImpenetrable(const Body&), SetImpenetrable(Body&).
Examples
World.cpp, and WorldContact.cpp.

Referenced by playrho::d2::World::SetImpenetrable(), and playrho::d2::World::UnsetImpenetrable().

◆ UnsetImpenetrable() [2/2]

void playrho::d2::UnsetImpenetrable ( World world,
BodyID  id 
)

Unsets the impenetrable status of the identified body.

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

◆ Validate()

bool playrho::d2::Validate ( const Span< const Length2 > &  verts)

Validates the convexity of the given collection of vertices.

Note
This is a time consuming operation.
Returns
true if the given collection of vertices is indeed convex, false otherwise.

◆ ValidateMetrics()

bool playrho::d2::ValidateMetrics ( const DynamicTree tree,
DynamicTree::Size  index 
)
noexcept

Validates the metrics of the given tree from the given index.

Note
Meant for testing.
Returns
true if valid, false otherwise.

◆ ValidateStructure()

bool playrho::d2::ValidateStructure ( const DynamicTree tree,
DynamicTree::Size  index 
)
noexcept

Validates the structure of the given tree from the given index.

Note
Meant for testing.
Returns
true if valid, false otherwise.

Variable Documentation

◆ EarthlyGravity

constexpr auto playrho::d2::EarthlyGravity = LinearAcceleration2{0_mps2, EarthlyLinearAcceleration}
constexpr

Earthly gravity in 2-dimensions.

Linear acceleration in 2-dimensions of an earthly object due to Earth's mass.

See also
EarthlyLinearAcceleration
Examples
HelloWorld.cpp, RevoluteJoint.cpp, and World.cpp.

◆ InvalidAABB

constexpr auto playrho::d2::InvalidAABB
constexpr
Initial value:
= AABB{
LengthInterval{Invalid<Length>},
LengthInterval{Invalid<Length>}
}
Interval< Length > LengthInterval
Length Interval alias.
Definition: Intervals.hpp:38
::playrho::detail::AABB< 2 > AABB
2-Dimensional Axis Aligned Bounding Box.
Definition: AABB.hpp:63

Invalid AABB value.

◆ IsValidJointTypeV

template<class T >
constexpr bool playrho::d2::IsValidJointTypeV = detail::IsValidJointType<T>::value
inlineconstexpr

Boolean value for whether the specified type is a valid joint type.

See also
Joint.

◆ Transform_identity

constexpr auto playrho::d2::Transform_identity
constexpr
Initial value:
= Transformation{
Length2{0_m, 0_m}, UnitVec::GetRight()
}
Vector2< Length > Length2
2-element vector of Length quantities.
Definition: Vector2.hpp:51

Identity transformation value.