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

Name space for 2-dimensionally related PlayRho names. More...

Classes

struct  Acceleration
 2-D acceleration related data structure. More...
 
struct  BaseShapeConf
 Base configuration for initializing shapes. More...
 
class  Body
 Physical entity that exists within a World. More...
 
struct  BodyConf
 Configuration for a body. More...
 
class  BodyConstraint
 Constraint for a body. More...
 
class  ChainShapeConf
 Chain shape configuration. More...
 
struct  ClipVertex
 Clip vertex. More...
 
class  Contact
 A potential contact between the children of two Fixture objects. More...
 
class  ContactImpulsesList
 Contact Impulse. More...
 
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...
 
class  EdgeShapeConf
 Edge shape configuration. More...
 
struct  FixtureConf
 Fixture definition. More...
 
struct  FrictionJointConf
 Friction joint definition. More...
 
struct  GearJointConf
 Gear joint definition. More...
 
struct  Island
 Definition of a self-contained constraint "island". More...
 
struct  IsValidJointType
 An "is valid joint type" trait. More...
 
struct  IsValidJointType< T, std::void_t< decltype(GetBodyA(std::declval< T >())), decltype(GetBodyB(std::declval< T >())), decltype(GetCollideConnected(std::declval< T >())), decltype(ShiftOrigin(std::declval< T & >(), std::declval< Length2 >())), decltype(InitVelocity(std::declval< T & >(), std::declval< std::vector< BodyConstraint > & >(), std::declval< StepConf >(), std::declval< ConstraintSolverConf >())), decltype(SolveVelocity(std::declval< T & >(), std::declval< std::vector< BodyConstraint > & >(), std::declval< StepConf >())), decltype(SolvePosition(std::declval< T >(), std::declval< std::vector< BodyConstraint > & >(), std::declval< ConstraintSolverConf >())), decltype(std::declval< T >()==std::declval< T >()), decltype(Joint{std::declval< T >()})> >
 An "is valid joint type" trait. More...
 
struct  IsValidShapeType
 An "is valid shape type" trait. More...
 
struct  IsValidShapeType< T, std::void_t< decltype(GetChildCount(std::declval< T >())), decltype(GetChild(std::declval< T >(), std::declval< ChildCounter >())), decltype(GetMassData(std::declval< T >())), decltype(GetVertexRadius(std::declval< T >(), std::declval< ChildCounter >())), decltype(GetDensity(std::declval< T >())), decltype(GetFriction(std::declval< T >())), decltype(GetRestitution(std::declval< T >())), decltype(Transform(std::declval< T & >(), std::declval< Mat22 >())), decltype(std::declval< T >()==std::declval< T >()), decltype(Shape{std::declval< T >()})> >
 An "is valid shape type" trait. 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  JointKey
 Joint key. 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  PolygonShapeConf
 Polygon shape configuration. More...
 
struct  Position
 2-D positional data structure. More...
 
class  PositionConstraint
 The per-contact position constraint data structure. More...
 
struct  PositionSolution
 Solution for position constraint. More...
 
struct  PositionSolverManifold
 Position solver manifold. 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  SeparationScenario
 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...
 
class  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  WorldImpl
 Definition of a "world" implementation. 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. More...
 
using ClipList = ArrayList< ClipVertex, MaxManifoldPoints >
 Clip list for ClipSegmentToLine. More...
 
using DynamicTreeSizeCB = std::function< DynamicTreeOpcode(DynamicTree::Size)>
 Query callback type.
 
using QueryFixtureCallback = std::function< bool(FixtureID fixture, ChildCounter child)>
 Query AABB for fixtures callback function type. More...
 
using LengthIndices = ::playrho::detail::LengthIndices< 2 >
 Length and vertex counter array of indices for 2-D space.
 
using SeparationInfo = ::playrho::detail::SeparationInfo< 2 >
 Separation information alias for 2-D space.
 
using MassData = ::playrho::detail::MassData< 2 >
 Mass data alias for 2-D objects. More...
 
using RayCastInput = playrho::detail::RayCastInput< 2 >
 Ray cast input data for 2-dimensions.
 
using RayCastOutput = std::optional< RayCastHit >
 Ray cast output. More...
 
using DynamicTreeRayCastCB = std::function< Real(BodyID body, FixtureID fixture, ChildCounter child, const RayCastInput &input)>
 Ray cast callback function. More...
 
using FixtureRayCastCB = std::function< RayCastOpcode(BodyID body, FixtureID fixture, ChildCounter child, Length2 point, UnitVec normal)>
 Ray cast callback function signature.
 
using SimplexEdges = ArrayList< SimplexEdge, MaxSimplexEdges, std::remove_const< decltype(MaxSimplexEdges)>::type >
 Simplex edge collection. More...
 
using VelocityPair = std::pair< Velocity, Velocity >
 Velocity pair.
 
using KeyedContactPtr = std::pair< ContactKey, ContactID >
 Keyed contact pointer.
 
using BodyConstraints = std::vector< BodyConstraint >
 Collection of body constraints.
 
using PositionConstraints = std::vector< PositionConstraint >
 Collection of position constraints.
 
using VelocityConstraints = std::vector< VelocityConstraint >
 Collection of velocity constraints.
 

Enumerations

enum  DynamicTreeOpcode { End, Continue }
 Opcodes for dynamic tree callbacks.
 
enum  LimitState { LimitState::e_inactiveLimit, LimitState::e_atLowerLimit, LimitState::e_atUpperLimit, LimitState::e_equalLimits }
 Limit state. More...
 

Functions

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) noexcept
 Computes the AABB for the given shape with the given transformation.
 
AABB ComputeAABB (const World &world, FixtureID id)
 Computes the AABB for the identified fixture within the given world.
 
AABB ComputeAABB (const World &world, BodyID id)
 Computes the AABB for the identified body within the given world.
 
AABB ComputeIntersectingAABB (const World &world, FixtureID fA, ChildCounter iA, FixtureID fB, ChildCounter iB) noexcept
 Computes the intersecting AABB for the given pair of fixtures and indexes. More...
 
AABB ComputeIntersectingAABB (const World &world, const Contact &contact)
 Computes the intersecting AABB for the given contact.
 
AABB GetAABB (const playrho::detail::RayCastInput< 2 > &input) noexcept
 Gets the AABB for the given ray cast input data. <2>
 
constexpr Length GetPerimeter (const AABB &aabb) noexcept
 Gets the perimeter length of the 2-dimensional AABB. More...
 
PointStates GetPointStates (const Manifold &manifold1, const Manifold &manifold2) noexcept
 Computes the point states given two manifolds.
 
ClipList ClipSegmentToLine (const ClipList &vIn, const UnitVec &normal, Length offset, ContactFeature::Index indexA)
 Clipping for contact manifolds. More...
 
DistanceConf GetDistanceConf (const ToiConf &conf) noexcept
 Gets the distance configuration for the given time of impact configuration.
 
DistanceConf GetDistanceConf (const StepConf &conf) noexcept
 Gets the distance configuration for the given step configuration.
 
PairLength2 GetWitnessPoints (const Simplex &simplex) noexcept
 Gets the witness points of the given simplex.
 
DistanceOutput Distance (const DistanceProxy &proxyA, const Transformation &transformA, const DistanceProxy &proxyB, const Transformation &transformB, DistanceConf conf=DistanceConf{})
 Determines the closest points between two shapes. More...
 
Area TestOverlap (const DistanceProxy &proxyA, const Transformation &xfA, const DistanceProxy &proxyB, const Transformation &xfB, DistanceConf conf=DistanceConf{})
 Determine if two generic shapes overlap. More...
 
constexpr Length2 GetDelta (PairLength2 arg) noexcept
 Gets the delta to go from the first element to the second.
 
bool operator== (const DistanceProxy &lhs, const DistanceProxy &rhs) noexcept
 Determines with the two given distance proxies are equal.
 
std::size_t FindLowestRightMostVertex (Span< const Length2 > vertices)
 Finds the lowest right most vertex in the given collection.
 
std::vector< Length2GetConvexHullAsVector (Span< const Length2 > vertices)
 Gets the convex hull for the given collection of vertices as a vector.
 
bool TestPoint (const DistanceProxy &proxy, Length2 point) noexcept
 Tests a point for containment in the given distance proxy. More...
 
bool operator!= (const DistanceProxy &lhs, const DistanceProxy &rhs) noexcept
 Determines with the two given distance proxies are not equal.
 
NonNegative< LengthGetVertexRadius (const DistanceProxy &arg) noexcept
 Gets the vertex radius property of a given distance proxy.
 
template<class T >
VertexCounter GetSupportIndex (const DistanceProxy &proxy, T dir) noexcept
 Gets the supporting vertex index in the given direction for the given distance proxy. More...
 
void swap (DynamicTree &lhs, DynamicTree &rhs) noexcept
 
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, QueryFixtureCallback callback)
 Queries the world for all fixtures that potentially overlap the provided AABB. More...
 
Length ComputeTotalPerimeter (const DynamicTree &tree) noexcept
 Gets the sum of the perimeters of nodes. More...
 
Real ComputePerimeterRatio (const DynamicTree &tree) noexcept
 Gets the ratio of the sum of the perimeters of nodes to the root perimeter. More...
 
DynamicTree::Height ComputeHeight (const DynamicTree &tree, DynamicTree::Size index) noexcept
 Computes the height of the tree from a given node. More...
 
DynamicTree::Height GetMaxImbalance (const DynamicTree &tree) noexcept
 Gets the maximum imbalance. More...
 
bool ValidateStructure (const DynamicTree &tree, DynamicTree::Size index) noexcept
 Validates the structure of the given tree from the given index. More...
 
bool ValidateMetrics (const DynamicTree &tree, DynamicTree::Size index) noexcept
 Validates the metrics of the given tree from the given index. More...
 
constexpr bool operator== (const DynamicTree::LeafData &lhs, const DynamicTree::LeafData &rhs) noexcept
 Equality operator.
 
constexpr bool operator!= (const DynamicTree::LeafData &lhs, const DynamicTree::LeafData &rhs) noexcept
 Inequality operator.
 
constexpr bool IsUnused (const DynamicTree::TreeNode &node) noexcept
 Is unused. More...
 
constexpr bool IsLeaf (const DynamicTree::TreeNode &node) noexcept
 Is leaf. More...
 
constexpr bool IsBranch (const DynamicTree::TreeNode &node) noexcept
 Is branch. More...
 
constexpr DynamicTree::BranchData ReplaceChild (DynamicTree::BranchData bd, DynamicTree::Size oldChild, DynamicTree::Size newChild)
 Replaces the old child with the new child.
 
constexpr AABB GetAABB (const DynamicTree::TreeNode &node) noexcept
 Gets the AABB of the given dynamic tree node.
 
constexpr DynamicTree::Size GetNext (const DynamicTree::TreeNode &node) noexcept
 Gets the next index of the given node. More...
 
DynamicTree::Height GetHeight (const DynamicTree &tree) noexcept
 Gets the height of the binary tree. More...
 
AABB GetAABB (const DynamicTree &tree) noexcept
 Gets the AABB for the given dynamic tree. 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.
 
DynamicTree::Height ComputeHeight (const DynamicTree &tree) noexcept
 Computes the height of the given dynamic tree.
 
std::size_t size (const DynamicTree &tree) noexcept
 Gets the "size" of the given tree. More...
 
Manifold::Conf GetManifoldConf (const StepConf &conf) noexcept
 Gets the manifold configuration for the given step configuration.
 
Manifold GetManifold (bool flipped, const DistanceProxy &shape0, const Transformation &xf0, const VertexCounter idx0, const DistanceProxy &shape1, const Transformation &xf1, const 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, Length2 point, const Transformation &xfm)
 Computes manifolds for face-to-point collision. More...
 
Manifold GetManifold (Length2 locationA, const Transformation &xfA, Length2 locationB, const Transformation &xfB, Length totalRadius) noexcept
 Gets a point-to-point based manifold.
 
Manifold CollideShapes (const DistanceProxy &shapeA, const Transformation &xfA, const DistanceProxy &shapeB, const Transformation &xfB, Manifold::Conf conf=GetDefaultManifoldConf())
 Calculates the relevant collision manifold. More...
 
const char * GetName (Manifold::Type type) noexcept
 Gets a unique name for the given manifold type.
 
bool operator== (const Manifold::Point &lhs, const Manifold::Point &rhs) noexcept
 Determines whether the two given manifold points are equal.
 
bool operator!= (const Manifold::Point &lhs, const Manifold::Point &rhs) noexcept
 Determines whether the two given manifold points are not equal.
 
bool operator== (const Manifold &lhs, const Manifold &rhs) noexcept
 Manifold equality operator. More...
 
bool operator!= (const Manifold &lhs, const Manifold &rhs) noexcept
 Manifold inequality operator. More...
 
constexpr Manifold::Conf GetDefaultManifoldConf () noexcept
 Gets the default manifold configuration.
 
MassData GetMassData (Length r, NonNegative< AreaDensity > density, Length2 location)
 Computes the mass data for a circular shape. More...
 
MassData GetMassData (Length r, NonNegative< AreaDensity > density, Length2 v0, 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.
 
RayCastOutput RayCast (Length radius, Length2 location, const RayCastInput &input) noexcept
 Cast a ray against a circle of a given radius at the given location. 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...
 
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 DynamicTree &tree, RayCastInput input, const DynamicTreeRayCastCB &callback)
 Cast rays against the leafs in the given tree. More...
 
bool RayCast (const World &world, const RayCastInput &input, const FixtureRayCastCB &callback)
 Ray-cast the world for all fixtures in the path of the ray. More...
 
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...
 
LengthIndexPair FindMinSeparation (const SeparationScenario &scenario, const Transformation &xfA, const Transformation &xfB)
 Finds the minimum separation. More...
 
Length Evaluate (const SeparationScenario &scenario, const Transformation &xfA, const Transformation &xfB, IndexPair indexPair)
 Evaluates the separation of the identified proxy vertices at the given time factor. More...
 
ChainShapeConf GetChainShapeConf (Length2 dimensions)
 Gets an enclosing chain shape configuration for an axis aligned rectangle of the given dimensions (width and height).
 
ChainShapeConf GetChainShapeConf (const AABB &arg)
 Gets an enclosing chain shape configuration for the given axis aligned box.
 
ChildCounter GetChildCount (const ChainShapeConf &arg) noexcept
 Gets the child count for a given chain shape configuration.
 
DistanceProxy GetChild (const ChainShapeConf &arg, ChildCounter index)
 Gets the "child" shape for a given chain shape configuration.
 
MassData GetMassData (const ChainShapeConf &arg) noexcept
 Gets the mass data for a given chain shape configuration.
 
bool IsLooped (const ChainShapeConf &shape) noexcept
 Determines whether the given shape is looped.
 
ChildCounter GetNextIndex (const ChainShapeConf &shape, ChildCounter index) noexcept
 Gets the next index after the given index for the given shape.
 
NonNegative< LengthGetVertexRadius (const ChainShapeConf &arg)
 Gets the vertex radius of the given shape configuration.
 
NonNegative< LengthGetVertexRadius (const ChainShapeConf &arg, ChildCounter)
 Gets the vertex radius of the given shape configuration.
 
void Transform (ChainShapeConf &arg, const Mat22 &m) noexcept
 Transforms the given chain shape configuration's vertices by the given transformation matrix. More...
 
ChainShapeConf GetChainShapeConf (Length dimension)
 Gets an enclosing chain shape configuration for an axis aligned square of the given dimension.
 
bool operator== (const DiskShapeConf &lhs, const DiskShapeConf &rhs) noexcept
 Equality operator.
 
bool operator!= (const DiskShapeConf &lhs, const DiskShapeConf &rhs) noexcept
 Inequality operator.
 
constexpr ChildCounter GetChildCount (const DiskShapeConf &) noexcept
 Gets the "child" count of the given disk shape configuration.
 
DistanceProxy GetChild (const DiskShapeConf &arg, ChildCounter index)
 Gets the "child" of the given disk 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.
 
MassData GetMassData (const DiskShapeConf &arg) noexcept
 Gets the mass data of the given disk shape configuration.
 
void Transform (DiskShapeConf &arg, const Mat22 &m) noexcept
 Transforms the given shape configuration's vertices by the given transformation matrix. More...
 
bool operator== (const EdgeShapeConf &lhs, const EdgeShapeConf &rhs) noexcept
 Equality operator.
 
bool operator!= (const EdgeShapeConf &lhs, const EdgeShapeConf &rhs) noexcept
 Inequality operator.
 
constexpr ChildCounter GetChildCount (const EdgeShapeConf &) noexcept
 Gets the "child" count for the given shape configuration. More...
 
DistanceProxy GetChild (const EdgeShapeConf &arg, ChildCounter index)
 Gets the "child" shape for the given shape configuration.
 
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.
 
MassData GetMassData (const EdgeShapeConf &arg) noexcept
 Gets the mass data for the given shape configuration.
 
void Transform (EdgeShapeConf &arg, const Mat22 &m) noexcept
 Transforms the given shape configuration's vertices by the given transformation matrix. More...
 
MassData GetMassData (const MultiShapeConf &arg) noexcept
 Computes the mass properties of this shape using its dimensions and density. The inertia tensor is computed about the local origin. More...
 
bool operator== (const MultiShapeConf &lhs, const MultiShapeConf &rhs) noexcept
 Equality operator.
 
bool operator!= (const MultiShapeConf &lhs, const MultiShapeConf &rhs) noexcept
 Inequality operator.
 
ChildCounter GetChildCount (const MultiShapeConf &arg) noexcept
 Gets the "child" count for the given shape configuration.
 
DistanceProxy GetChild (const MultiShapeConf &arg, ChildCounter index)
 Gets the "child" shape for the given shape configuration.
 
NonNegative< LengthGetVertexRadius (const MultiShapeConf &arg, ChildCounter index)
 Gets the vertex radius of the given shape configuration.
 
void Transform (MultiShapeConf &arg, const Mat22 &m) noexcept
 Transforms the given multi shape configuration by the given transformation matrix. More...
 
Length2 GetEdge (const PolygonShapeConf &shape, VertexCounter index)
 Gets the identified edge of the given polygon shape. More...
 
bool Validate (const Span< const Length2 > verts)
 Validates the convexity of the given collection of vertices. More...
 
constexpr ChildCounter GetChildCount (const PolygonShapeConf &) noexcept
 Gets the "child" count for the given shape configuration. More...
 
DistanceProxy GetChild (const PolygonShapeConf &arg, ChildCounter index)
 Gets the "child" shape for 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.
 
MassData GetMassData (const PolygonShapeConf &arg) noexcept
 Gets the mass data for the given shape configuration.
 
void Transform (PolygonShapeConf &arg, const Mat22 &m) noexcept
 Transforms the given polygon configuration's vertices by the given transformation matrix. More...
 
bool TestPoint (const Shape &shape, Length2 point) noexcept
 Test a point for containment in the given shape. More...
 
ChildCounter GetChildCount (const Shape &shape) noexcept
 Gets the number of child primitives of the shape. More...
 
DistanceProxy GetChild (const Shape &shape, ChildCounter index)
 Gets the "child" for the given index. More...
 
MassData GetMassData (const Shape &shape) noexcept
 Gets the mass properties of this shape using its dimensions and density. More...
 
Real GetFriction (const Shape &shape) noexcept
 Gets the coefficient of friction. More...
 
Real GetRestitution (const Shape &shape) noexcept
 Gets the coefficient of restitution value of the given shape.
 
NonNegative< AreaDensityGetDensity (const Shape &shape) noexcept
 Gets the density of the given shape. More...
 
NonNegative< LengthGetVertexRadius (const Shape &shape, ChildCounter idx)
 Gets the vertex radius of the indexed child of the given shape. More...
 
void Transform (Shape &shape, const Mat22 &m)
 Transforms all of the given shape's vertices by the given transformation matrix. More...
 
const void * GetData (const Shape &shape) noexcept
 Gets a pointer to the underlying data. More...
 
TypeID GetType (const Shape &shape) noexcept
 Gets the type info of the use of the given shape. 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...
 
bool operator== (const Shape &lhs, const Shape &rhs) noexcept
 Equality operator for shape to shape comparisons.
 
bool operator!= (const Shape &lhs, const Shape &rhs) noexcept
 Inequality operator for shape to shape comparisons.
 
template<typename T >
TypeCast (const Shape &value)
 Casts the specified instance into the template specified type. More...
 
constexpr NonNegative< AreaDensityGetDensity (const BaseShapeConf &arg) noexcept
 Gets the density of the given shape configuration.
 
constexpr Finite< RealGetRestitution (const BaseShapeConf &arg) noexcept
 Gets the restitution of the given shape configuration.
 
constexpr NonNegative< RealGetFriction (const BaseShapeConf &arg) noexcept
 Gets the friction of the given shape configuration.
 
SeparationInfo GetMaxSeparation4x4 (const DistanceProxy &proxy1, Transformation xf1, const DistanceProxy &proxy2, Transformation xf2)
 Gets the max separation information for the first four vertices of the two given shapes. More...
 
SeparationInfo GetMaxSeparation (const DistanceProxy &proxy1, Transformation xf1, const DistanceProxy &proxy2, Transformation xf2)
 Gets the max separation information. More...
 
SeparationInfo GetMaxSeparation (const DistanceProxy &proxy1, Transformation xf1, const DistanceProxy &proxy2, Transformation xf2, Length stop)
 Gets the max separation information. More...
 
SeparationInfo GetMaxSeparation (const DistanceProxy &proxy1, const DistanceProxy &proxy2, Length stop=MaxFloat *Meter)
 Gets the max separation information. More...
 
IndexPair3 GetIndexPairs (const SimplexEdges &collection) noexcept
 Gets index pairs for the given edges collection.
 
Length2 CalcSearchDirection (const SimplexEdges &simplexEdges) noexcept
 Calculates the "search direction" for the given simplex edge list. More...
 
Length2 GetScaledDelta (const Simplex &simplex, Simplex::size_type index)
 Gets the scaled delta for the given indexed element of the given simplex.
 
constexpr Length2 GetClosestPoint (const Simplex &simplex)
 Gets the "closest point".
 
constexpr Length2 GetPointDelta (const SimplexEdge &sv) noexcept
 Gets "w". More...
 
constexpr bool operator== (const SimplexEdge &lhs, const SimplexEdge &rhs) noexcept
 Equality operator for SimplexEdge.
 
constexpr bool operator!= (const SimplexEdge &lhs, const SimplexEdge &rhs) noexcept
 Inequality operator for SimplexEdge.
 
TOIOutput GetToiViaSat (const DistanceProxy &proxyA, const Sweep &sweepA, const DistanceProxy &proxyB, const Sweep &sweepB, ToiConf conf=GetDefaultToiConf())
 Gets the time of impact for two disjoint convex sets using the Separating Axis Theorem. More...
 
WorldManifold GetWorldManifold (const Manifold &manifold, Transformation xfA, Length radiusA, Transformation xfB, Length radiusB)
 Gets the world manifold for the given data. More...
 
WorldManifold GetWorldManifold (const World &world, const Contact &contact, const Manifold &manifold)
 Gets the world manifold for the given data. More...
 
constexpr bool operator== (const Acceleration &lhs, const Acceleration &rhs)
 Equality operator.
 
constexpr bool operator!= (const Acceleration &lhs, const Acceleration &rhs)
 Inequality operator.
 
constexpr Accelerationoperator*= (Acceleration &lhs, const Real rhs)
 Multiplication assignment operator.
 
constexpr Accelerationoperator/= (Acceleration &lhs, const Real rhs)
 Division assignment operator.
 
constexpr Accelerationoperator+= (Acceleration &lhs, const Acceleration &rhs)
 Addition assignment operator.
 
constexpr Acceleration operator+ (const Acceleration &lhs, const Acceleration &rhs)
 Addition operator.
 
constexpr Accelerationoperator-= (Acceleration &lhs, const Acceleration &rhs)
 Subtraction assignment operator.
 
constexpr Acceleration operator- (const Acceleration &lhs, const Acceleration &rhs)
 Subtraction operator.
 
constexpr Acceleration operator- (const Acceleration &value)
 Negation operator.
 
constexpr Acceleration operator+ (const Acceleration &value)
 Positive operator.
 
constexpr Acceleration operator* (const Acceleration &lhs, const Real rhs)
 Multiplication operator.
 
constexpr Acceleration operator* (const Real lhs, const Acceleration &rhs)
 Multiplication operator.
 
constexpr Acceleration operator/ (const Acceleration &lhs, const Real rhs)
 Division operator.
 
LinearVelocity2 GetContactRelVelocity (const Velocity velA, const Length2 relA, const Velocity velB, const Length2 relB) noexcept
 Gets the contact relative velocity. More...
 
constexpr Vec2 GetVec2 (const UnitVec value)
 Gets a Vec2 representation of the given value.
 
Angle GetAngle (const UnitVec value)
 Gets the angle of the given unit vector.
 
Angle GetAngle (const Transformation &value)
 Gets the angle of the given transformation.
 
template<class T , typename U >
constexpr Vector2< T > operator* (CheckedValue< T, U > s, UnitVec u) noexcept
 Multiplication operator.
 
template<class T >
constexpr Vector2< T > operator* (const T s, const UnitVec u) noexcept
 Multiplication operator.
 
template<class T , typename U >
constexpr Vector2< T > operator* (UnitVec u, CheckedValue< T, U > s) noexcept
 Multiplication operator.
 
template<class T >
constexpr Vector2< T > operator* (const UnitVec u, const T s) noexcept
 Multiplication operator.
 
constexpr Vec2 operator/ (const UnitVec u, const UnitVec::value_type s) noexcept
 Division operator.
 
template<class T >
constexpr auto Rotate (const Vector2< T > vector, const UnitVec &angle) noexcept
 Rotates a vector by a given angle. More...
 
template<class T >
constexpr auto InverseRotate (const Vector2< T > vector, const UnitVec &angle) noexcept
 Inverse rotates a vector. More...
 
template<class T >
UnitVec GetUnitVector (Vector2< T > value, UnitVec fallback=UnitVec::GetDefaultFallback())
 Gets the unit vector for the given value. More...
 
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...
 
constexpr Length2 Transform (const Length2 v, const Transformation xfm) noexcept
 Transforms the given 2-D vector with the given transformation. More...
 
constexpr Length2 InverseTransform (const Length2 v, const Transformation xfm) noexcept
 Inverse transforms the given 2-D vector with the given transformation. More...
 
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...
 
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 Real beta) noexcept
 Gets the interpolated transform at a specific time. More...
 
Transformation GetTransform0 (const Sweep &sweep) noexcept
 Gets the transform at "time" zero. More...
 
Transformation GetTransform1 (const Sweep &sweep) noexcept
 Gets the transform at "time" one. More...
 
bool IsUnderActive (Velocity velocity, LinearVelocity linSleepTol, AngularVelocity angSleepTol) noexcept
 Gets whether the given velocity is "under active" based on the given tolerances.
 
InvMass GetEffectiveInvMass (const InvRotInertia invRotI, const Length2 p, const UnitVec q)
 Gets the "effective" inverse mass.
 
constexpr auto GetReflectionMatrix (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...
 
constexpr bool operator== (const Position &lhs, const Position &rhs)
 Equality operator.
 
constexpr bool operator!= (const Position &lhs, const Position &rhs)
 Inequality operator.
 
constexpr Position operator- (const Position &value)
 Negation operator.
 
constexpr Position operator+ (const Position &value)
 Positive operator.
 
constexpr Positionoperator+= (Position &lhs, const Position &rhs)
 Addition assignment operator.
 
constexpr Position operator+ (const Position &lhs, const Position &rhs)
 Addition operator.
 
constexpr Positionoperator-= (Position &lhs, const Position &rhs)
 Subtraction assignment operator.
 
constexpr Position operator- (const Position &lhs, const Position &rhs)
 Subtraction operator.
 
constexpr Position operator* (const Position &pos, const Real scalar)
 Multiplication operator.
 
constexpr Position operator* (const Real scalar, const Position &pos)
 Multiplication operator.
 
constexpr Position GetPosition (const Position pos0, const Position pos1, const Real beta) noexcept
 Gets the position between two positions at a given unit interval. More...
 
constexpr bool operator== (const Sweep &lhs, const Sweep &rhs)
 Equals operator.
 
constexpr bool operator!= (const Sweep &lhs, const Sweep &rhs)
 Not-equals operator.
 
constexpr bool operator== (const Transformation &lhs, const Transformation &rhs) noexcept
 Equality operator.
 
constexpr bool operator!= (const Transformation &lhs, const Transformation &rhs) noexcept
 Inequality operator.
 
constexpr Length2 GetLocation (const Transformation &value) noexcept
 Gets the location information from the given transformation.
 
constexpr UnitVec GetDirection (const Transformation &value) noexcept
 Gets the directional information from the given transformation.
 
constexpr UnitVec GetXAxis (UnitVec rot) noexcept
 Gets the "X-axis".
 
constexpr UnitVec GetYAxis (UnitVec rot) noexcept
 Gets the "Y-axis". More...
 
constexpr bool operator== (const UnitVec a, const UnitVec b) noexcept
 Equality operator.
 
constexpr bool operator!= (const UnitVec a, const UnitVec b) noexcept
 Inequality operator.
 
constexpr UnitVec GetRevPerpendicular (const UnitVec vector) noexcept
 Gets a vector counter-clockwise (reverse-clockwise) perpendicular to the given vector. More...
 
constexpr UnitVec GetFwdPerpendicular (const UnitVec vector) noexcept
 Gets a vector clockwise (forward-clockwise) perpendicular to the given vector. More...
 
constexpr UnitVec Rotate (const UnitVec vector, const UnitVec &angle) noexcept
 Rotates a unit vector by the angle expressed by the second unit vector. More...
 
constexpr UnitVec InverseRotate (const UnitVec vector, const UnitVec &angle) noexcept
 Inverse rotates a vector.
 
template<std::size_t I>
constexpr UnitVec::value_type get (UnitVec v) noexcept
 Gets the specified element of the given collection.
 
template<>
constexpr UnitVec::value_type get< 0 > (UnitVec v) noexcept
 Gets element 0 of the given collection.
 
template<>
constexpr UnitVec::value_type get< 1 > (UnitVec v) noexcept
 Gets element 1 of the given collection.
 
inline ::std::ostream & operator<< (::std::ostream &os, const UnitVec &value)
 Output stream operator.
 
Velocity Cap (Velocity velocity, Time h, const MovementConf &conf) noexcept
 Caps velocity. More...
 
constexpr bool operator== (const Velocity &lhs, const Velocity &rhs)
 Equality operator.
 
constexpr bool operator!= (const Velocity &lhs, const Velocity &rhs)
 Inequality operator.
 
constexpr Velocityoperator*= (Velocity &lhs, const Real rhs)
 Multiplication assignment operator.
 
constexpr Velocityoperator/= (Velocity &lhs, const Real rhs)
 Division assignment operator.
 
constexpr Velocityoperator+= (Velocity &lhs, const Velocity &rhs)
 Addition assignment operator.
 
constexpr Velocity operator+ (const Velocity &lhs, const Velocity &rhs)
 Addition operator.
 
constexpr Velocityoperator-= (Velocity &lhs, const Velocity &rhs)
 Subtraction assignment operator.
 
constexpr Velocity operator- (const Velocity &lhs, const Velocity &rhs)
 Subtraction operator.
 
constexpr Velocity operator- (const Velocity &value)
 Negation operator.
 
constexpr Velocity operator+ (const Velocity &value)
 Positive operator.
 
constexpr Velocity operator* (const Velocity &lhs, const Real rhs)
 Multiplication operator.
 
constexpr Velocity operator* (const Real lhs, const Velocity &rhs)
 Multiplication operator.
 
constexpr Velocity operator/ (const Velocity &lhs, const Real rhs)
 Division operator.
 
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...
 
void ApplyLinearImpulse (Body &body, Momentum2 impulse, Length2 point) noexcept
 Applies an impulse at a point. More...
 
void ApplyAngularImpulse (Body &body, AngularMomentum impulse) noexcept
 Applies an angular impulse. More...
 
bool operator== (const Body &lhs, const Body &rhs)
 Equals operator.
 
BodyType GetType (const Body &body) noexcept
 Gets the type of this body. More...
 
void SetType (Body &body, BodyType value) noexcept
 Sets the type of this body. More...
 
bool IsSpeedable (const Body &body) noexcept
 Is "speedable". More...
 
bool IsAccelerable (const Body &body) noexcept
 Is "accelerable". More...
 
bool IsImpenetrable (const Body &body) noexcept
 Is this body treated like a bullet for continuous collision detection? More...
 
void SetImpenetrable (Body &body) noexcept
 Sets the impenetrable status of this body. More...
 
void UnsetImpenetrable (Body &body) noexcept
 Unsets the impenetrable status of this body. More...
 
bool IsSleepingAllowed (const Body &body) noexcept
 Gets whether or not this body allowed to sleep. More...
 
void SetSleepingAllowed (Body &body, bool value) noexcept
 You can disable sleeping on this body. If you disable sleeping, the body will be woken. More...
 
bool IsEnabled (const Body &body) noexcept
 Gets the enabled/disabled state of the body. More...
 
void SetEnabled (Body &body) noexcept
 Sets the enabled state. More...
 
void UnsetEnabled (Body &body) noexcept
 Unsets the enabled state. More...
 
void SetEnabled (Body &body, bool value) noexcept
 Sets the enabled state to the given value. More...
 
bool IsAwake (const Body &body) noexcept
 Gets the awake/asleep state of this body. More...
 
void SetAwake (Body &body) noexcept
 Awakens this body. More...
 
void UnsetAwake (Body &body) noexcept
 Sets this body to asleep if sleeping is allowed. More...
 
Transformation GetTransformation (const Body &body) noexcept
 Gets the body's transformation. More...
 
void SetTransformation (Body &body, Transformation value) noexcept
 Sets the body's transformation. More...
 
Length2 GetLocation (const Body &body) noexcept
 Gets the body's origin location. More...
 
const SweepGetSweep (const Body &body) noexcept
 Gets the body's sweep. More...
 
void SetSweep (Body &body, const Sweep &value) noexcept
 Sets the sweep value of the given body. More...
 
Position GetPosition1 (const Body &body) noexcept
 Gets the "position 1" Position information for the given body.
 
Angle GetAngle (const Body &body) noexcept
 Gets the body's angle. More...
 
Length2 GetWorldCenter (const Body &body) noexcept
 Get the world position of the center of mass.
 
Length2 GetLocalCenter (const Body &body) noexcept
 Gets the local position of the center of mass.
 
Position GetPosition (const Body &body) noexcept
 Gets the body's position.
 
Time GetUnderActiveTime (const Body &body) noexcept
 Gets the given body's under-active time. More...
 
bool IsFixedRotation (const Body &body) noexcept
 Does this body have fixed rotation? More...
 
void SetFixedRotation (Body &body, bool value)
 Sets this body to have fixed rotation. More...
 
bool IsMassDataDirty (const Body &body) noexcept
 Gets whether the mass data for this body is "dirty".
 
InvMass GetInvMass (const Body &body) noexcept
 Gets the inverse total mass of the body. More...
 
InvRotInertia GetInvRotInertia (const Body &body) noexcept
 Gets the inverse rotational inertia of the body. More...
 
Frequency GetLinearDamping (const Body &body) noexcept
 Gets the linear damping of the body. More...
 
void SetLinearDamping (Body &body, NonNegative< Frequency > value) noexcept
 Sets the linear damping of the body. More...
 
Frequency GetAngularDamping (const Body &body) noexcept
 Gets the angular damping of the body. More...
 
void SetAngularDamping (Body &body, NonNegative< Frequency > value) noexcept
 Sets the angular damping of the body. More...
 
Acceleration GetAcceleration (const Body &body) noexcept
 Gets the given body's acceleration. More...
 
void SetAcceleration (Body &body, Acceleration value) noexcept
 Sets the accelerations on the given body. More...
 
LinearAcceleration2 GetLinearAcceleration (const Body &body) noexcept
 Gets this body's linear acceleration. More...
 
AngularAcceleration GetAngularAcceleration (const Body &body) noexcept
 Gets this body's angular acceleration. More...
 
bool Awaken (Body &body) noexcept
 Awakens the body if it's asleep. More...
 
bool Unawaken (Body &body) noexcept
 Puts the body to sleep if it's awake. More...
 
Mass GetMass (const Body &body) noexcept
 Gets the mass of the body. More...
 
void SetMass (Body &body, Mass mass)
 Sets the mass of the given body.
 
void SetAcceleration (Body &body, LinearAcceleration2 linear, AngularAcceleration angular) noexcept
 Sets the linear and rotational accelerations on this body. More...
 
void SetAcceleration (Body &body, LinearAcceleration2 value) noexcept
 Sets the given linear acceleration of the given body. More...
 
void SetAcceleration (Body &body, AngularAcceleration value) noexcept
 Sets the given angular acceleration of the given body. More...
 
RotInertia GetRotInertia (const Body &body) noexcept
 Gets the rotational inertia of the body. More...
 
RotInertia GetLocalRotInertia (const Body &body) noexcept
 Gets the rotational inertia of the body about the local origin. More...
 
Velocity GetVelocity (const Body &body) noexcept
 Gets the velocity. More...
 
void SetVelocity (Body &body, const Velocity &value) noexcept
 Sets the body's velocity (linear and angular velocity). More...
 
LinearVelocity2 GetLinearVelocity (const Body &body) noexcept
 Gets the linear velocity of the center of mass. More...
 
AngularVelocity GetAngularVelocity (const Body &body) noexcept
 Gets the angular velocity. More...
 
void SetVelocity (Body &body, LinearVelocity2 value) noexcept
 Sets the linear velocity of the center of mass. More...
 
void SetVelocity (Body &body, AngularVelocity value) noexcept
 Sets the angular velocity. 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 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.
 
Length2 GetLocalPoint (const Body &body, const Length2 worldPoint) noexcept
 Gets a local point relative to the body's origin given a world point. More...
 
UnitVec GetLocalVector (const Body &body, const UnitVec uv) noexcept
 Gets a locally oriented unit vector given a world oriented unit vector. More...
 
LinearVelocity2 GetLinearVelocityFromWorldPoint (const Body &body, const Length2 worldPoint) noexcept
 Gets the linear velocity from a world point attached to this body. More...
 
LinearVelocity2 GetLinearVelocityFromLocalPoint (const Body &body, const Length2 localPoint) noexcept
 Gets the linear velocity from a local point. More...
 
Force2 GetForce (const Body &body) noexcept
 Gets the net force that the given body is currently experiencing.
 
Torque GetTorque (const Body &body) noexcept
 Gets the net torque that the given body is currently experiencing.
 
bool operator!= (const Body &lhs, const Body &rhs)
 Not-equals operator.
 
BodyConf GetBodyConf (const Body &body) noexcept
 Gets the body definition for the given body. More...
 
Transformation GetTransformation (const BodyConf &conf) noexcept
 Gets the transformation associated with the given configuration.
 
constexpr BodyConf GetDefaultBodyConf () noexcept
 Gets the default body definition.
 
constexpr Angle GetAngle (const BodyConf &conf) noexcept
 Gets the angle of the given configuration.
 
constexpr bool operator== (const BodyConf &lhs, const BodyConf &rhs) noexcept
 Operator equals.
 
constexpr bool operator!= (const BodyConf &lhs, const BodyConf &rhs) noexcept
 Operator not-equals.
 
ContactImpulsesList GetContactImpulses (const VelocityConstraint &vc)
 Gets the contact impulses for the given velocity constraint.
 
Momentum GetMaxNormalImpulse (const ContactImpulsesList &impulses) noexcept
 Gets the maximum normal impulse from the given contact impulses list.
 
BodyConstraint GetBodyConstraint (const Body &body, Time time, MovementConf conf) noexcept
 Gets the BodyConstraint based on the given parameters.
 
BodyID GetBodyA (const Contact &contact) noexcept
 Gets the body A ID of the given contact.
 
BodyID GetBodyB (const Contact &contact) noexcept
 Gets the body B ID of the given contact.
 
FixtureID GetFixtureA (const Contact &contact) noexcept
 Gets the fixture A associated with the given contact.
 
FixtureID GetFixtureB (const Contact &contact) noexcept
 Gets the fixture B associated with the given contact.
 
ChildCounter GetChildIndexA (const Contact &contact) noexcept
 Gets the child index A of the given contact.
 
ChildCounter GetChildIndexB (const Contact &contact) noexcept
 Gets the child index B of the given contact.
 
bool IsImpenetrable (const Contact &contact) noexcept
 Whether the given contact is "impenetrable".
 
bool IsActive (const Contact &contact) noexcept
 Determines whether the given contact is "active".
 
bool IsEnabled (const Contact &contact) noexcept
 Gets whether the given contact is enabled or not.
 
void SetEnabled (Contact &contact) noexcept
 Enables the identified contact. More...
 
void UnsetEnabled (Contact &contact) noexcept
 Disables the identified contact. More...
 
bool IsTouching (const Contact &contact) noexcept
 Gets whether the given contact is touching or not.
 
bool IsSensor (const Contact &contact) noexcept
 Gets whether the given contact is for sensors or not.
 
auto GetToiCount (const Contact &contact) noexcept
 Gets the time of impact count.
 
auto NeedsFiltering (const Contact &contact) noexcept
 Whether or not the contact needs filtering.
 
auto NeedsUpdating (const Contact &contact) noexcept
 Whether or not the contact needs updating.
 
auto HasValidToi (const Contact &contact) noexcept
 Gets whether a TOI is set. More...
 
Real GetToi (const Contact &contact) noexcept
 Gets the time of impact (TOI) as a fraction. More...
 
auto GetFriction (const Contact &contact) noexcept
 Gets the coefficient of friction. More...
 
void SetFriction (Contact &contact, Real value) noexcept
 Sets the friction value for the identified contact. More...
 
auto GetRestitution (const Contact &contact) noexcept
 Gets the coefficient of restitution. More...
 
void SetRestitution (Contact &contact, Real value)
 Sets the restitution value for the identified contact. More...
 
auto GetTangentSpeed (const Contact &contact) noexcept
 Gets the desired tangent speed. More...
 
void SetTangentSpeed (Contact &contact, LinearVelocity value) noexcept
 Sets the desired tangent speed for a conveyor belt behavior. More...
 
PositionSolution operator+ (PositionSolution lhs, PositionSolution rhs)
 Addition operator.
 
PositionSolution operator- (PositionSolution lhs, PositionSolution rhs)
 Subtraction operator.
 
ContactID GetContactPtr (KeyedContactPtr value)
 Gets the contact ID for the given value.
 
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...
 
VelocityConstraint::Conf GetRegVelocityConstraintConf (const StepConf &conf) noexcept
 Gets the regular phase velocity constraint configuration from the given step configuration.
 
VelocityConstraint::Conf GetToiVelocityConstraintConf (const StepConf &conf) noexcept
 Gets the TOI phase velocity constraint configuration from the given step configuration.
 
UnitVec GetNormal (const VelocityConstraint &vc) noexcept
 Gets the normal of the velocity constraint contact in world coordinates. More...
 
UnitVec GetTangent (const VelocityConstraint &vc) noexcept
 Gets the tangent from the given velocity constraint data.
 
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.
 
LinearVelocity GetVelocityBiasAtPoint (const VelocityConstraint &vc, VelocityConstraint::size_type index)
 Gets the velocity bias at the given point from the given velocity constraint.
 
Mass GetNormalMassAtPoint (const VelocityConstraint &vc, VelocityConstraint::size_type index)
 Gets the normal mass at the given point from 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.
 
Momentum GetNormalImpulseAtPoint (const VelocityConstraint &vc, VelocityConstraint::size_type index)
 Gets the normal impulse at the given point from the given velocity constraint.
 
Momentum GetTangentImpulseAtPoint (const VelocityConstraint &vc, VelocityConstraint::size_type index)
 Gets the tangent impulse at the given point from the given velocity constraint.
 
Momentum2 GetNormalImpulses (const VelocityConstraint &vc)
 Gets the normal impulses of the given velocity constraint.
 
Momentum2 GetTangentImpulses (const VelocityConstraint &vc)
 Gets the tangent impulses of the given velocity constraint.
 
void SetNormalImpulseAtPoint (VelocityConstraint &vc, VelocityConstraint::size_type index, Momentum value)
 Sets the normal impulse at the given point of the given velocity constraint.
 
void SetTangentImpulseAtPoint (VelocityConstraint &vc, VelocityConstraint::size_type index, Momentum value)
 Sets the tangent 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 SetTangentImpulses (VelocityConstraint &vc, const Momentum2 impulses)
 Sets the tangent impulses of the given velocity constraint.
 
Real GetDefaultFriction (const FixtureConf &fixtureA, const FixtureConf &fixtureB)
 Gets the default friction amount for the given fixtures.
 
Real GetDefaultRestitution (const FixtureConf &fixtureA, const FixtureConf &fixtureB)
 Gets the default restitution amount for the given fixtures.
 
bool operator== (const FixtureConf &lhs, const FixtureConf &rhs)
 Operator equals.
 
bool operator!= (const FixtureConf &lhs, const FixtureConf &rhs)
 Operator not-equals.
 
BodyID GetBody (const FixtureConf &conf) noexcept
 Gets the body of the given configuration.
 
const ShapeGetShape (const FixtureConf &conf) noexcept
 Gets the shape of the given configuration.
 
NonNegative< AreaDensityGetDensity (const FixtureConf &conf) noexcept
 Gets the density of the given configuration.
 
Real GetFriction (const FixtureConf &conf) noexcept
 Gets the friction of the given configuration.
 
Real GetRestitution (const FixtureConf &conf) noexcept
 Gets the restitution of the given configuration.
 
bool IsSensor (const FixtureConf &conf) noexcept
 Gets whether or not the given configuration is a sensor.
 
void SetSensor (FixtureConf &conf, bool value) noexcept
 Sets whether or not the given configuration is a sensor.
 
Filter GetFilterData (const FixtureConf &conf) noexcept
 Gets the filter-data of the given configuration.
 
void SetFilterData (FixtureConf &conf, Filter value) noexcept
 Sets the filter-data of the given configuration.
 
bool ShouldCollide (const FixtureConf &fixtureA, const FixtureConf &fixtureB) noexcept
 Whether contact calculations should be performed between the two fixtures. More...
 
void Reserve (Island &island, BodyCounter bodies, ContactCounter contacts, JointCounter joints)
 Reserves space ahead of time.
 
void Clear (Island &island) noexcept
 Clears the island containers.
 
std::size_t Count (const Island &island, BodyID entry)
 Counts the number of occurrences of the given entry in the given island.
 
std::size_t Count (const Island &island, ContactID entry)
 Counts the number of occurrences of the given entry in the given island.
 
std::size_t Count (const Island &island, JointID entry)
 Counts the number of occurrences of the given entry in the given island.
 
bool IsFullOfBodies (const Island &island)
 Determines whether the given island is full of bodies.
 
bool IsFullOfContacts (const Island &island)
 Determines whether the given island is full of contacts.
 
DistanceJointConf GetDistanceJointConf (const Joint &joint) noexcept
 Gets the definition data for the given joint.
 
DistanceJointConf GetDistanceJointConf (const World &world, BodyID bodyA, BodyID bodyB, Length2 anchorA=Length2{}, Length2 anchorB=Length2{})
 Gets the configuration for the given parameters.
 
void InitVelocity (DistanceJointConf &object, std::vector< BodyConstraint > &bodies, const StepConf &step, const ConstraintSolverConf &conf)
 Initializes velocity constraint data based on the given solver data. More...
 
bool SolveVelocity (DistanceJointConf &object, std::vector< BodyConstraint > &bodies, const StepConf &step)
 Solves velocity constraint. More...
 
bool SolvePosition (const DistanceJointConf &object, std::vector< BodyConstraint > &bodies, const ConstraintSolverConf &conf)
 Solves the position constraint. More...
 
constexpr bool operator== (const DistanceJointConf &lhs, const DistanceJointConf &rhs) noexcept
 Equality operator.
 
constexpr bool operator!= (const DistanceJointConf &lhs, const DistanceJointConf &rhs) noexcept
 Inequality operator.
 
constexpr Momentum2 GetLinearReaction (const DistanceJointConf &object) noexcept
 Gets the current linear reaction for the given configuration.
 
constexpr AngularMomentum GetAngularReaction (const DistanceJointConf &) noexcept
 Gets the current angular reaction for the given configuration.
 
constexpr bool ShiftOrigin (DistanceJointConf &, Length2) noexcept
 Shifts the origin notion of the given configuration.
 
constexpr void SetFrequency (DistanceJointConf &object, NonNegative< Frequency > value) noexcept
 Free function for setting the frequency 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 auto GetLength (const DistanceJointConf &object) noexcept
 Free function for getting the length value of the given configuration.
 
constexpr auto SetLength (DistanceJointConf &object, Length value) noexcept
 Free function for setting the length value of the given configuration.
 
FrictionJointConf GetFrictionJointConf (const Joint &joint) noexcept
 Gets the definition data for the given joint.
 
FrictionJointConf GetFrictionJointConf (const World &world, BodyID bodyA, BodyID bodyB, Length2 anchor)
 Gets the confguration for the given parameters.
 
void InitVelocity (FrictionJointConf &object, std::vector< BodyConstraint > &bodies, const StepConf &step, const ConstraintSolverConf &conf)
 Initializes velocity constraint data based on the given solver data. More...
 
bool SolveVelocity (FrictionJointConf &object, std::vector< BodyConstraint > &bodies, const StepConf &step)
 Solves velocity constraint. More...
 
bool SolvePosition (const FrictionJointConf &object, std::vector< BodyConstraint > &bodies, const ConstraintSolverConf &conf)
 Solves the position constraint. More...
 
constexpr bool operator== (const FrictionJointConf &lhs, const FrictionJointConf &rhs) noexcept
 Equality operator.
 
constexpr bool operator!= (const FrictionJointConf &lhs, const FrictionJointConf &rhs) noexcept
 Inequality operator.
 
constexpr Momentum2 GetLinearReaction (const FrictionJointConf &object) noexcept
 Gets the current linear reaction for the given configuration.
 
constexpr AngularMomentum GetAngularReaction (const FrictionJointConf &object) noexcept
 Gets the current angular reaction for the given configuration.
 
constexpr bool ShiftOrigin (FrictionJointConf &, Length2) noexcept
 Shifts the origin notion of the given configuration.
 
constexpr auto GetMaxForce (const FrictionJointConf &object) noexcept
 Free function for getting the max force value of the given configuration.
 
constexpr void SetMaxForce (FrictionJointConf &object, NonNegative< Force > value) noexcept
 Free function for setting the max force value of the given configuration.
 
constexpr auto GetMaxTorque (const FrictionJointConf &object) noexcept
 Free function for getting the max torque value of the given configuration.
 
constexpr auto SetMaxTorque (FrictionJointConf &object, NonNegative< Torque > value) noexcept
 Free function for setting the max force value of the given configuration.
 
GearJointConf GetGearJointConf (const Joint &joint) noexcept
 Gets the definition data for the given joint.
 
GearJointConf GetGearJointConf (const World &world, JointID id1, JointID id2, Real ratio=Real{1})
 Gets the configuration for the given parameters.
 
void InitVelocity (GearJointConf &object, std::vector< BodyConstraint > &bodies, const StepConf &step, const ConstraintSolverConf &conf)
 Initializes velocity constraint data based on the given solver data. More...
 
bool SolveVelocity (GearJointConf &object, std::vector< BodyConstraint > &bodies, const StepConf &step)
 Solves velocity constraint. More...
 
bool SolvePosition (const GearJointConf &object, std::vector< BodyConstraint > &bodies, const ConstraintSolverConf &conf)
 Solves the position constraint. More...
 
constexpr bool operator== (const GearJointConf &lhs, const GearJointConf &rhs) noexcept
 Equality operator.
 
constexpr bool operator!= (const GearJointConf &lhs, const GearJointConf &rhs) noexcept
 Inequality operator.
 
constexpr Momentum2 GetLinearReaction (const GearJointConf &object)
 Gets the current linear reaction for the given configuration.
 
constexpr AngularMomentum GetAngularReaction (const GearJointConf &object)
 Gets the current angular reaction for the given configuration.
 
constexpr bool ShiftOrigin (GearJointConf &, Length2) noexcept
 Shifts the origin notion of the given configuration.
 
constexpr auto GetRatio (const GearJointConf &object) noexcept
 Free function for getting the ratio value of the given configuration.
 
constexpr auto SetRatio (GearJointConf &object, Real value) noexcept
 Free function for setting the ratio value of the given configuration.
 
constexpr auto GetConstant (const GearJointConf &object) noexcept
 Free function for getting the constant value of the given configuration.
 
constexpr auto GetType1 (const GearJointConf &object) noexcept
 Free function for getting joint 1 type value of the given configuration.
 
constexpr auto GetType2 (const GearJointConf &object) noexcept
 Free function for getting joint 2 type value of the given configuration.
 
BodyConstraintAt (std::vector< BodyConstraint > &container, BodyID key)
 Provides referenced access to the identified element of the given container.
 
Length2 GetLocalAnchorA (const Joint &object)
 Get the anchor point on body-A in local coordinates.
 
Length2 GetLocalAnchorB (const Joint &object)
 Get the anchor point on body-B in local coordinates.
 
Momentum2 GetLinearReaction (const Joint &object)
 Get the linear reaction on body-B at the joint anchor.
 
AngularMomentum GetAngularReaction (const Joint &object)
 Get the angular reaction on body-B.
 
Angle GetReferenceAngle (const Joint &object)
 Gets the reference angle of the joint if it has one. More...
 
UnitVec GetLocalXAxisA (const Joint &object)
 Gets the given joint's local X axis A if its type supports that. More...
 
UnitVec GetLocalYAxisA (const Joint &object)
 Gets the given joint's local Y axis A if its type supports that. More...
 
AngularVelocity GetMotorSpeed (const Joint &object)
 Gets the given joint's motor speed if its type supports that. More...
 
void SetMotorSpeed (Joint &object, AngularVelocity value)
 Sets the given joint's motor speed if its type supports that. More...
 
RotInertia GetAngularMass (const Joint &object)
 Gets the given joint's angular mass. More...
 
Force GetMaxForce (const Joint &object)
 Gets the given joint's max force if its type supports that. More...
 
Torque GetMaxTorque (const Joint &object)
 Gets the given joint's max torque if its type supports that. More...
 
Force GetMaxMotorForce (const Joint &object)
 Gets the given joint's max motor force if its type supports that. More...
 
void SetMaxMotorForce (Joint &object, Force value)
 Sets the given joint's max motor force if its type supports that. More...
 
Torque GetMaxMotorTorque (const Joint &object)
 Gets the given joint's max motor torque if its type supports that. More...
 
void SetMaxMotorTorque (Joint &object, Torque value)
 Sets the given joint's max motor torque if its type supports that. More...
 
Real GetRatio (const Joint &object)
 Gets the given joint's ratio property if it has one. More...
 
Real GetDampingRatio (const Joint &object)
 Gets the given joint's damping ratio property if it has one. More...
 
Frequency GetFrequency (const Joint &object)
 Gets the frequency of the joint if it has this property. More...
 
void SetFrequency (Joint &object, Frequency value)
 Sets the frequency of the joint if it has this property. More...
 
AngularMomentum GetAngularMotorImpulse (const Joint &object)
 Gets the angular motor impulse of the joint if it has this property. More...
 
Length2 GetTarget (const Joint &object)
 Gets the given joint's target property if it has one. More...
 
void SetTarget (Joint &object, Length2 value)
 Sets the given joint's target property if it has one. More...
 
Length GetLinearLowerLimit (const Joint &object)
 Gets the lower linear joint limit. More...
 
Length GetLinearUpperLimit (const Joint &object)
 Gets the upper linear joint limit. More...
 
void SetLinearLimits (Joint &object, Length lower, Length upper)
 Sets the joint limits. More...
 
Angle GetAngularLowerLimit (const Joint &object)
 Gets the lower joint limit. More...
 
Angle GetAngularUpperLimit (const Joint &object)
 Gets the upper joint limit. More...
 
void SetAngularLimits (Joint &object, Angle lower, Angle upper)
 Sets the joint limits. More...
 
bool IsLimitEnabled (const Joint &object)
 Gets the specified joint's limit property if it supports one. More...
 
void EnableLimit (Joint &object, bool value)
 Enables the specified joint's limit property if it supports one. More...
 
bool IsMotorEnabled (const Joint &object)
 Gets the specified joint's motor property value if it supports one. More...
 
void EnableMotor (Joint &object, bool value)
 Enables the specified joint's motor property if it supports one. More...
 
Length2 GetLinearOffset (const Joint &object)
 Gets the linear offset property of the specified joint if its type has one. More...
 
void SetLinearOffset (Joint &object, Length2 value)
 Sets the linear offset property of the specified joint if its type has one. More...
 
Angle GetAngularOffset (const Joint &object)
 Gets the angular offset property of the specified joint if its type has one. More...
 
void SetAngularOffset (Joint &object, Angle value)
 Sets the angular offset property of the specified joint if its type has one. More...
 
LimitState GetLimitState (const Joint &object)
 
Length2 GetGroundAnchorA (const Joint &object)
 
Length2 GetGroundAnchorB (const Joint &object)
 
Momentum GetLinearMotorImpulse (const Joint &object)
 
Length GetLength (const Joint &object)
 Gets the length property of the specified joint if its type has one. More...
 
TypeID GetType (const Joint &object) noexcept
 Gets the identifier of the type of data this can be casted to.
 
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 >
std::add_pointer_t< T > TypeCast (Joint *value) noexcept
 Converts the given joint into its current configuration value. More...
 
bool operator== (const Joint &lhs, const Joint &rhs) noexcept
 Equality operator for joint comparisons.
 
bool operator!= (const Joint &lhs, const Joint &rhs) noexcept
 Inequality operator for joint comparisons.
 
BodyID GetBodyA (const Joint &object) noexcept
 Gets the first body attached to this joint.
 
BodyID GetBodyB (const Joint &object) noexcept
 Gets the second body attached to this joint.
 
bool GetCollideConnected (const Joint &object) noexcept
 Gets collide connected. More...
 
bool ShiftOrigin (Joint &object, Length2 value) noexcept
 Shifts the origin for any points stored in world coordinates. More...
 
void InitVelocity (Joint &object, std::vector< BodyConstraint > &bodies, const StepConf &step, const ConstraintSolverConf &conf)
 Initializes velocity constraint data based on the given solver data. More...
 
bool SolveVelocity (Joint &object, std::vector< BodyConstraint > &bodies, const StepConf &step)
 Solves velocity constraint. More...
 
bool SolvePosition (const Joint &object, std::vector< BodyConstraint > &bodies, const ConstraintSolverConf &conf)
 Solves the position constraint. More...
 
template<typename T >
TypeCast (const 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 >
TypeCast (Joint &&value)
 Converts the given joint into its current configuration value. More...
 
Torque GetMotorTorque (const Joint &joint, Frequency inv_dt)
 Gets the current motor torque for the given joint given the inverse time step. More...
 
void Set (JointConf &def, const Joint &joint) noexcept
 Sets the joint definition data for the given joint.
 
constexpr BodyID GetBodyA (const JointConf &object) noexcept
 Gets the first body attached to this joint.
 
constexpr BodyID GetBodyB (const JointConf &object) noexcept
 Gets the second body attached to this joint.
 
constexpr bool GetCollideConnected (const JointConf &object) noexcept
 Gets whether attached bodies should collide or not.
 
template<typename T >
constexpr auto IsLimitEnabled (const T &conf) noexcept -> decltype(std::declval< T >().enableLimit)
 
template<typename T >
constexpr auto EnableLimit (T &conf, bool v) noexcept -> decltype(std::declval< T >().UseEnableLimit(bool
 
template<typename T >
constexpr auto GetLength (const T &conf) noexcept -> decltype(std::declval< T >().length)
 
template<typename T >
constexpr auto GetMaxForce (const T &conf) noexcept -> decltype(std::declval< T >().maxForce)
 
template<typename T >
constexpr auto GetMaxTorque (const T &conf) noexcept -> decltype(std::declval< T >().maxTorque)
 
template<typename T >
constexpr auto GetRatio (const T &conf) noexcept -> decltype(std::declval< T >().ratio)
 
template<typename T >
constexpr auto GetDampingRatio (const T &conf) noexcept -> decltype(std::declval< T >().dampingRatio)
 
template<typename T >
constexpr auto GetReferenceAngle (const T &conf) noexcept -> decltype(std::declval< T >().referenceAngle)
 
template<typename T >
constexpr auto GetLinearReaction (const T &conf) noexcept -> decltype(std::declval< T >().linearImpulse)
 
template<typename T >
constexpr auto GetLinearOffset (const T &conf) noexcept -> decltype(std::declval< T >().linearOffset)
 
template<typename T >
constexpr auto GetLimitState (const T &conf) noexcept -> decltype(std::declval< T >().limitState)
 
template<typename T >
constexpr auto GetGroundAnchorA (const T &conf) noexcept -> decltype(std::declval< T >().groundAnchorA)
 
template<typename T >
constexpr auto GetGroundAnchorB (const T &conf) noexcept -> decltype(std::declval< T >().groundAnchorB)
 
template<typename T >
constexpr auto GetLocalAnchorA (const T &conf) noexcept -> decltype(std::declval< T >().localAnchorA)
 
template<typename T >
constexpr auto GetLocalAnchorB (const T &conf) noexcept -> decltype(std::declval< T >().localAnchorB)
 
template<typename T >
constexpr auto GetLocalXAxisA (const T &conf) noexcept -> decltype(std::declval< T >().localXAxisA)
 
template<typename T >
constexpr auto GetLocalYAxisA (const T &conf) noexcept -> decltype(std::declval< T >().localYAxisA)
 
template<typename T >
constexpr auto GetFrequency (const T &conf) noexcept -> decltype(std::declval< T >().frequency)
 
template<typename T >
constexpr auto IsMotorEnabled (const T &conf) noexcept -> decltype(std::declval< T >().enableMotor)
 
template<typename T >
constexpr auto EnableMotor (T &conf, bool v) noexcept -> decltype(std::declval< T >().UseEnableMotor(bool
 
template<typename T >
constexpr auto GetMotorSpeed (const T &conf) noexcept -> decltype(std::declval< T >().motorSpeed)
 
template<typename T >
constexpr auto SetMotorSpeed (T &conf, AngularVelocity v) noexcept -> decltype(std::declval< T >().UseMotorSpeed(AngularVelocity
 
template<typename T >
constexpr auto GetLinearMotorImpulse (const T &conf) noexcept -> decltype(std::declval< T >().motorImpulse)
 
template<typename T >
constexpr auto GetMaxMotorForce (const T &conf) noexcept -> decltype(std::declval< T >().maxMotorForce)
 
template<typename T >
constexpr auto GetMaxMotorTorque (const T &conf) noexcept -> decltype(std::declval< T >().maxMotorTorque)
 
template<typename T >
constexpr auto GetAngularOffset (const T &conf) noexcept -> decltype(std::declval< T >().angularOffset)
 
template<typename T >
constexpr auto GetAngularReaction (const T &conf) noexcept -> decltype(std::declval< T >().angularImpulse)
 
template<typename T >
constexpr auto GetAngularMass (const T &conf) noexcept -> decltype(std::declval< T >().angularMass)
 
template<typename T >
constexpr auto GetAngularMotorImpulse (const T &conf) noexcept -> decltype(std::declval< T >().angularMotorImpulse)
 
JointKey GetJointKey (const Joint &joint) noexcept
 Gets the JointKey for the given joint.
 
constexpr int Compare (const JointKey &lhs, const JointKey &rhs) noexcept
 Compares the given joint keys.
 
constexpr bool IsFor (const JointKey key, BodyID body) noexcept
 Determines whether the given key is for the given body.
 
const char * ToString (LimitState val) noexcept
 Provides a human readable C-style string uniquely identifying the given limit state.
 
MotorJointConf GetMotorJointConf (const Joint &joint) noexcept
 Gets the definition data for the given joint.
 
MotorJointConf GetMotorJointConf (const World &world, BodyID bA, BodyID bB)
 Gets the confguration for the given parameters.
 
void InitVelocity (MotorJointConf &object, std::vector< BodyConstraint > &bodies, const StepConf &step, const ConstraintSolverConf &conf)
 Initializes velocity constraint data based on the given solver data. More...
 
bool SolveVelocity (MotorJointConf &object, std::vector< BodyConstraint > &bodies, const StepConf &step)
 Solves velocity constraint. More...
 
bool SolvePosition (const MotorJointConf &object, std::vector< BodyConstraint > &bodies, const ConstraintSolverConf &conf)
 Solves the position constraint. More...
 
constexpr bool operator== (const MotorJointConf &lhs, const MotorJointConf &rhs) noexcept
 Equality operator.
 
constexpr bool operator!= (const MotorJointConf &lhs, const MotorJointConf &rhs) noexcept
 Inequality operator.
 
constexpr auto GetLocalAnchorA (const MotorJointConf &) noexcept
 Gets the local anchor A.
 
constexpr auto GetLocalAnchorB (const MotorJointConf &) noexcept
 Gets the local anchor B.
 
constexpr auto ShiftOrigin (MotorJointConf &, Length2) noexcept
 Shifts the origin notion of the given configuration.
 
constexpr auto GetMaxForce (const MotorJointConf &object) noexcept
 Free function for getting the maximum 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 GetMaxTorque (const MotorJointConf &object) noexcept
 Free function for getting the maximum torque 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.
 
constexpr auto GetLinearError (const MotorJointConf &object) noexcept
 Free function for getting the linear error value of the given configuration.
 
constexpr auto GetAngularError (const MotorJointConf &object) noexcept
 Free function for getting the angular error value of the given configuration.
 
constexpr auto GetLinearOffset (const MotorJointConf &object) noexcept
 Free function for getting the linear offset value of the given configuration.
 
constexpr auto SetLinearOffset (MotorJointConf &object, Length2 value) noexcept
 Free function for setting the linear offset value of the given configuration.
 
constexpr auto GetAngularOffset (const MotorJointConf &object) noexcept
 Free function for getting the angular offset value of the given configuration.
 
constexpr auto SetAngularOffset (MotorJointConf &object, Angle value) noexcept
 Free function for setting the angular offset value of the given configuration.
 
constexpr auto GetCorrectionFactor (const MotorJointConf &object) noexcept
 Free function for getting the correction factor value of the given configuration.
 
constexpr auto SetCorrectionFactor (MotorJointConf &object, Real value) noexcept
 Free function for setting the correction factor value of the given configuration.
 
PrismaticJointConf GetPrismaticJointConf (const Joint &joint)
 Gets the definition data for the given joint.
 
PrismaticJointConf GetPrismaticJointConf (const World &world, BodyID bA, BodyID bB, const Length2 anchor, const UnitVec axis)
 Gets the configuration for the given parameters.
 
Momentum2 GetLinearReaction (const PrismaticJointConf &conf)
 Gets the current linear reaction of the given configuration.
 
AngularMomentum GetAngularReaction (const PrismaticJointConf &conf)
 Gets the current angular reaction of the given configuration.
 
void InitVelocity (PrismaticJointConf &object, std::vector< BodyConstraint > &bodies, const StepConf &step, const ConstraintSolverConf &conf)
 Initializes velocity constraint data based on the given solver data. More...
 
bool SolveVelocity (PrismaticJointConf &object, std::vector< BodyConstraint > &bodies, const StepConf &step)
 Solves velocity constraint. More...
 
bool SolvePosition (const PrismaticJointConf &object, std::vector< BodyConstraint > &bodies, const ConstraintSolverConf &conf)
 Solves the position constraint. More...
 
LinearVelocity GetLinearVelocity (const World &world, const PrismaticJointConf &joint) noexcept
 Gets the current linear velocity of the given configuration.
 
constexpr bool operator== (const PrismaticJointConf &lhs, const PrismaticJointConf &rhs) noexcept
 Equality operator.
 
constexpr bool operator!= (const PrismaticJointConf &lhs, const PrismaticJointConf &rhs) noexcept
 Inequality operator.
 
constexpr auto GetLinearLowerLimit (const PrismaticJointConf &conf) noexcept
 Free function for getting the linear lower limit value of the given configuration.
 
constexpr auto GetLinearUpperLimit (const PrismaticJointConf &conf) noexcept
 Free function for getting the linear upper limit value of the given configuration.
 
constexpr void SetLinearLimits (PrismaticJointConf &conf, Length lower, Length upper) noexcept
 Free function for setting the linear limits of the given configuration.
 
constexpr auto ShiftOrigin (PrismaticJointConf &, Length2) noexcept
 Shifts the origin notion of the given configuration.
 
constexpr void SetMaxMotorForce (PrismaticJointConf &object, Force value)
 Free function for setting the maximum motor torque value of the given configuration.
 
PulleyJointConf GetPulleyJointConf (const Joint &joint)
 Gets the definition data for the given joint.
 
PulleyJointConf GetPulleyJointConf (const World &world, BodyID bA, BodyID bB, Length2 groundA, Length2 groundB, Length2 anchorA, Length2 anchorB)
 Gets the configuration for the given parameters.
 
void InitVelocity (PulleyJointConf &object, std::vector< BodyConstraint > &bodies, const StepConf &step, const ConstraintSolverConf &conf)
 Initializes velocity constraint data based on the given solver data. More...
 
bool SolveVelocity (PulleyJointConf &object, std::vector< BodyConstraint > &bodies, const StepConf &step)
 Solves velocity constraint. More...
 
bool SolvePosition (const PulleyJointConf &object, std::vector< BodyConstraint > &bodies, const ConstraintSolverConf &conf)
 Solves the position constraint. More...
 
bool ShiftOrigin (PulleyJointConf &object, Length2 newOrigin) noexcept
 Shifts the origin notion of the given configuration.
 
constexpr bool operator== (const PulleyJointConf &lhs, const PulleyJointConf &rhs) noexcept
 Equality operator.
 
constexpr bool operator!= (const PulleyJointConf &lhs, const PulleyJointConf &rhs) noexcept
 Inequality operator.
 
constexpr Momentum2 GetLinearReaction (const PulleyJointConf &object) noexcept
 Gets the current linear reaction of the given configuration.
 
constexpr AngularMomentum GetAngularReaction (const PulleyJointConf &) noexcept
 Gets the current angular reaction of the given configuration.
 
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.
 
constexpr auto SetRatio (PulleyJointConf &object, Real value) noexcept
 Free function for setting the ratio value of the given configuration.
 
RevoluteJointConf GetRevoluteJointConf (const Joint &joint)
 Gets the definition data for the given joint.
 
RevoluteJointConf GetRevoluteJointConf (const World &world, BodyID bodyA, BodyID bodyB, Length2 anchor)
 Gets the configuration for the given parameters.
 
Angle GetAngle (const World &world, const RevoluteJointConf &conf)
 Gets the current angle of the given configuration in the given world.
 
AngularVelocity GetAngularVelocity (const World &world, const RevoluteJointConf &conf)
 Gets the current angular velocity of the given configuration.
 
void InitVelocity (RevoluteJointConf &object, std::vector< BodyConstraint > &bodies, const StepConf &step, const ConstraintSolverConf &conf)
 Initializes velocity constraint data based on the given solver data. More...
 
bool SolveVelocity (RevoluteJointConf &object, std::vector< BodyConstraint > &bodies, const StepConf &step)
 Solves velocity constraint. More...
 
bool SolvePosition (const RevoluteJointConf &object, std::vector< BodyConstraint > &bodies, const ConstraintSolverConf &conf)
 Solves the position constraint. More...
 
constexpr bool operator== (const RevoluteJointConf &lhs, const RevoluteJointConf &rhs) noexcept
 Equality operator.
 
constexpr bool operator!= (const RevoluteJointConf &lhs, const RevoluteJointConf &rhs) noexcept
 Inequality operator.
 
constexpr auto ShiftOrigin (RevoluteJointConf &, Length2) noexcept
 Shifts the origin notion of the given configuration.
 
constexpr Angle GetAngularLowerLimit (const RevoluteJointConf &conf) noexcept
 Free function for getting the angular lower limit value of the given configuration.
 
constexpr Angle GetAngularUpperLimit (const RevoluteJointConf &conf) noexcept
 Free function for getting the angular upper limit value of the given configuration.
 
constexpr Momentum2 GetLinearReaction (const RevoluteJointConf &conf) noexcept
 Gets the current linear reaction of the given configuration.
 
constexpr AngularMomentum GetAngularReaction (const RevoluteJointConf &conf) noexcept
 Gets the current angular reaction of the given configuration.
 
constexpr void SetAngularLimits (RevoluteJointConf &object, Angle lower, Angle upper) noexcept
 Free function for setting the angular limits of the given configuration.
 
constexpr void SetMaxMotorTorque (RevoluteJointConf &object, Torque value)
 Free function for setting the max motor torque of the given configuration.
 
RopeJointConf GetRopeJointConf (const Joint &joint) noexcept
 Gets the definition data for the given joint.
 
void InitVelocity (RopeJointConf &object, std::vector< BodyConstraint > &bodies, const StepConf &step, const ConstraintSolverConf &conf)
 Initializes velocity constraint data based on the given solver data. More...
 
bool SolveVelocity (RopeJointConf &object, std::vector< BodyConstraint > &bodies, const StepConf &step)
 Solves velocity constraint. More...
 
bool SolvePosition (const RopeJointConf &object, std::vector< BodyConstraint > &bodies, const ConstraintSolverConf &conf)
 Solves the position constraint. More...
 
constexpr bool operator== (const RopeJointConf &lhs, const RopeJointConf &rhs) noexcept
 Equality operator.
 
constexpr bool operator!= (const RopeJointConf &lhs, const RopeJointConf &rhs) noexcept
 Inequality operator.
 
constexpr Momentum2 GetLinearReaction (const RopeJointConf &object) noexcept
 Gets the current linear reaction of the given configuration.
 
constexpr AngularMomentum GetAngularReaction (const RopeJointConf &) noexcept
 Gets the current angular reaction of the given configuration.
 
constexpr auto ShiftOrigin (RopeJointConf &, Length2) noexcept
 Shifts the origin notion of the given configuration.
 
constexpr auto GetMaxLength (const RopeJointConf &object) noexcept
 Free function for getting the maximum length 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.
 
TargetJointConf GetTargetJointConf (const Joint &joint)
 Gets the definition data for the given joint.
 
Mass22 GetEffectiveMassMatrix (const TargetJointConf &object, const BodyConstraint &body) noexcept
 Gets the effective mass matrix for the given configuration and body information.
 
void InitVelocity (TargetJointConf &object, std::vector< BodyConstraint > &bodies, const StepConf &step, const ConstraintSolverConf &conf)
 Initializes velocity constraint data based on the given solver data. More...
 
bool SolveVelocity (TargetJointConf &object, std::vector< BodyConstraint > &bodies, const StepConf &step)
 Solves velocity constraint. More...
 
bool SolvePosition (const TargetJointConf &object, std::vector< BodyConstraint > &bodies, const ConstraintSolverConf &conf)
 Solves the position constraint. More...
 
constexpr bool operator== (const TargetJointConf &lhs, const TargetJointConf &rhs) noexcept
 Equality operator.
 
constexpr bool operator!= (const TargetJointConf &lhs, const TargetJointConf &rhs) noexcept
 Inequality operator.
 
constexpr auto GetLocalAnchorA (const TargetJointConf &) noexcept
 Gets the local anchar A for the given configuration.
 
constexpr Momentum2 GetLinearReaction (const TargetJointConf &object)
 Gets the current linear reaction of the given configuration.
 
constexpr AngularMomentum GetAngularReaction (const TargetJointConf &)
 Gets the current angular reaction of the given configuration.
 
constexpr bool ShiftOrigin (TargetJointConf &object, Length2 newOrigin)
 Shifts the origin notion of the given configuration.
 
constexpr auto GetTarget (const TargetJointConf &object) noexcept
 Free function for getting the target value of the given configuration.
 
constexpr void SetTarget (TargetJointConf &object, Length2 value) noexcept
 Free function for setting the target value of the given configuration.
 
constexpr auto GetMaxForce (const TargetJointConf &object) noexcept
 Free function for getting 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 void SetFrequency (TargetJointConf &object, NonNegative< Frequency > value) noexcept
 Free function for setting the frequency 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.
 
WeldJointConf GetWeldJointConf (const Joint &joint)
 Gets the definition data for the given joint.
 
WeldJointConf GetWeldJointConf (const World &world, BodyID bodyA, BodyID bodyB, const Length2 anchor=Length2{})
 Gets the configuration for the given parameters.
 
void InitVelocity (WeldJointConf &object, std::vector< BodyConstraint > &bodies, const StepConf &step, const ConstraintSolverConf &conf)
 Initializes velocity constraint data based on the given solver data. More...
 
bool SolveVelocity (WeldJointConf &object, std::vector< BodyConstraint > &bodies, const StepConf &)
 Solves velocity constraint. More...
 
bool SolvePosition (const WeldJointConf &object, std::vector< BodyConstraint > &bodies, const ConstraintSolverConf &conf)
 Solves the position constraint. More...
 
constexpr bool operator== (const WeldJointConf &lhs, const WeldJointConf &rhs) noexcept
 Equality operator.
 
constexpr bool operator!= (const WeldJointConf &lhs, const WeldJointConf &rhs) noexcept
 Inequality operator.
 
constexpr Momentum2 GetLinearReaction (const WeldJointConf &object) noexcept
 Gets the current linear reaction of the given configuration.
 
constexpr AngularMomentum GetAngularReaction (const WeldJointConf &object) noexcept
 Gets the current angular reaction of the given configuration.
 
constexpr auto ShiftOrigin (WeldJointConf &, Length2) noexcept
 Shifts the origin notion 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 SetDampingRatio (WeldJointConf &object, Real value) noexcept
 Free function for setting the damping ratio of the given configuration.
 
WheelJointConf GetWheelJointConf (const Joint &joint)
 Gets the definition data for the given joint.
 
WheelJointConf GetWheelJointConf (const World &world, BodyID bodyA, BodyID bodyB, Length2 anchor, UnitVec axis=UnitVec::GetRight())
 Gets the definition data for the given parameters.
 
AngularVelocity GetAngularVelocity (const World &world, const WheelJointConf &conf)
 Gets the angular velocity for the given configuration within the specified world.
 
void InitVelocity (WheelJointConf &object, std::vector< BodyConstraint > &bodies, const StepConf &step, const ConstraintSolverConf &conf)
 Initializes velocity constraint data based on the given solver data. More...
 
bool SolveVelocity (WheelJointConf &object, std::vector< BodyConstraint > &bodies, const StepConf &step)
 Solves velocity constraint. More...
 
bool SolvePosition (const WheelJointConf &object, std::vector< BodyConstraint > &bodies, const ConstraintSolverConf &conf)
 Solves the position constraint. More...
 
constexpr bool operator== (const WheelJointConf &lhs, const WheelJointConf &rhs) noexcept
 Equality operator.
 
constexpr bool operator!= (const WheelJointConf &lhs, const WheelJointConf &rhs) noexcept
 Inequality operator.
 
constexpr Momentum2 GetLinearReaction (const WheelJointConf &object)
 Gets the current linear reaction for the given configuration.
 
constexpr auto ShiftOrigin (WheelJointConf &, Length2)
 Shifts the origin notion of the given configuration.
 
constexpr void SetMaxMotorTorque (WheelJointConf &object, Torque value) noexcept
 Sets the maximum motor torque for the given configuration.
 
constexpr void SetFrequency (WheelJointConf &object, NonNegative< Frequency > value) noexcept
 Free function for setting the frequency of the given configuration.
 
constexpr void SetDampingRatio (WheelJointConf &object, Real value) noexcept
 Free function for setting the damping ratio of the given configuration.
 
BodyCounter GetBodyRange (const World &world) noexcept
 Gets the extent of the currently valid body range. More...
 
SizedRange< std::vector< BodyID >::const_iterator > GetBodies (const World &world) noexcept
 Gets the bodies of the specified world.
 
SizedRange< std::vector< BodyID >::const_iterator > GetBodiesForProxies (const World &world) noexcept
 Gets the bodies-for-proxies range for the given world.
 
BodyID CreateBody (World &world, const BodyConf &def=GetDefaultBodyConf())
 Creates a rigid body with the given configuration. More...
 
const BodyGetBody (const World &world, BodyID id)
 Gets the body configuration for the identified body. More...
 
void SetBody (World &world, BodyID id, const Body &body)
 Sets the body state for the identified body. More...
 
void Destroy (World &world, BodyID id)
 Destroys the identified body. More...
 
SizedRange< std::vector< FixtureID >::const_iterator > GetFixtures (const World &world, BodyID id)
 Gets the range of all constant fixtures attached to the given body. More...
 
LinearAcceleration2 GetLinearAcceleration (const World &world, BodyID id)
 Gets this body's linear acceleration. More...
 
AngularAcceleration GetAngularAcceleration (const World &world, BodyID id)
 Gets this body's angular acceleration. More...
 
Acceleration GetAcceleration (const World &world, BodyID id)
 Gets the acceleration of the identified body. More...
 
void SetAcceleration (World &world, BodyID id, LinearAcceleration2 linear, AngularAcceleration angular)
 Sets the linear and rotational accelerations on the body. More...
 
void SetAcceleration (World &world, BodyID id, LinearAcceleration2 value)
 Sets the linear accelerations on the body. More...
 
void SetAcceleration (World &world, BodyID id, AngularAcceleration value)
 Sets the rotational accelerations on the body. More...
 
void SetAcceleration (World &world, BodyID id, Acceleration value)
 Sets the accelerations on the given body. More...
 
void SetTransformation (World &world, BodyID id, Transformation xfm)
 Sets the transformation of the body. More...
 
void SetLocation (World &world, BodyID id, Length2 value)
 Sets the body's location. More...
 
void SetAngle (World &world, BodyID id, Angle value)
 Sets the body's angular orientation. More...
 
void RotateAboutWorldPoint (World &world, BodyID id, Angle amount, Length2 worldPoint)
 Rotates a body a given amount around a point in world coordinates. More...
 
void RotateAboutLocalPoint (World &world, BodyID id, Angle amount, Length2 localPoint)
 Rotates a body a given amount around a point in body local coordinates. More...
 
Acceleration CalcGravitationalAcceleration (const World &world, BodyID id)
 Calculates the gravitationally associated acceleration for the given body within its world. More...
 
BodyCounter GetWorldIndex (const World &world, const BodyID id) noexcept
 Gets the world index for the given body. More...
 
BodyType GetType (const World &world, BodyID id)
 Gets the type of the identified body. More...
 
void SetType (World &world, BodyID id, BodyType value, bool resetMassData=true)
 Sets the type of the given body. More...
 
Transformation GetTransformation (const World &world, BodyID id)
 Gets the body's transformation. More...
 
Angle GetAngle (const World &world, BodyID id)
 Gets the angle of the identified body. More...
 
Velocity GetVelocity (const World &world, BodyID id)
 Gets the velocity of the identified body. More...
 
void SetVelocity (World &world, BodyID id, const Velocity &value)
 Sets the body's velocity (linear and angular velocity). More...
 
void SetVelocity (World &world, BodyID id, const LinearVelocity2 &value)
 Sets the velocity of the identified body. More...
 
void SetVelocity (World &world, BodyID id, AngularVelocity value)
 Sets the velocity of the identified body. More...
 
void DestroyFixtures (World &world, BodyID id, bool resetMassData=true)
 Destroys fixtures of the identified body. More...
 
bool IsEnabled (const World &world, BodyID id)
 Gets the enabled/disabled state of the body. More...
 
void SetEnabled (World &world, BodyID id, bool value)
 Sets the enabled state of the body. More...
 
bool IsAwake (const World &world, BodyID id)
 Gets the awake/asleep state of this body. More...
 
void SetAwake (World &world, BodyID id)
 Wakes up the identified body. More...
 
void UnsetAwake (World &world, BodyID id)
 Sleeps the identified body. More...
 
bool IsMassDataDirty (const World &world, BodyID id)
 Gets whether the body's mass-data is dirty. More...
 
bool IsFixedRotation (const World &world, BodyID id)
 Gets whether the body has fixed rotation. More...
 
void SetFixedRotation (World &world, BodyID id, bool value)
 Sets this body to have fixed rotation. More...
 
Length2 GetWorldCenter (const World &world, BodyID id)
 Get the world position of the center of mass of the specified body. More...
 
InvMass GetInvMass (const World &world, BodyID id)
 Gets the inverse total mass of the body. More...
 
InvRotInertia GetInvRotInertia (const World &world, BodyID id)
 Gets the inverse rotational inertia of the body. More...
 
Length2 GetLocalCenter (const World &world, BodyID id)
 Gets the local position of the center of mass of the specified body. More...
 
MassData ComputeMassData (const World &world, BodyID id)
 Computes the identified body's mass data. More...
 
void SetMassData (World &world, BodyID id, const MassData &massData)
 Sets the mass properties to override the mass properties of the fixtures. More...
 
SizedRange< std::vector< std::pair< BodyID, JointID > >::const_iterator > GetJoints (const World &world, BodyID id)
 Gets the range of all joints attached to the identified body. More...
 
bool IsSpeedable (const World &world, BodyID id)
 Is identified body "speedable". More...
 
bool IsAccelerable (const World &world, BodyID id)
 Is identified body "accelerable"? More...
 
bool IsImpenetrable (const World &world, BodyID id)
 Is the body treated like a bullet for continuous collision detection? More...
 
void SetImpenetrable (World &world, BodyID id)
 Sets the impenetrable status of the identified body. More...
 
void UnsetImpenetrable (World &world, BodyID id)
 Unsets the impenetrable status of the identified body. More...
 
bool IsSleepingAllowed (const World &world, BodyID id)
 Gets whether the identified body is allowed to sleep. More...
 
void SetSleepingAllowed (World &world, BodyID, bool value)
 Sets whether the identified body is allowed to sleep. More...
 
Frequency GetLinearDamping (const World &world, BodyID id)
 Gets the linear damping of the body. More...
 
void SetLinearDamping (World &world, BodyID id, NonNegative< Frequency > linearDamping)
 Sets the linear damping of the body. More...
 
Frequency GetAngularDamping (const World &world, BodyID id)
 Gets the angular damping of the body. More...
 
void SetAngularDamping (World &world, BodyID id, NonNegative< Frequency > angularDamping)
 Sets the angular damping of the body. More...
 
SizedRange< std::vector< KeyedContactPtr >::const_iterator > GetContacts (const World &world, BodyID id)
 Gets the container of all contacts attached to the identified body. More...
 
Force2 GetCentripetalForce (const World &world, BodyID id, Length2 axis)
 Gets the centripetal force necessary to put the body into an orbit having the given radius. More...
 
void ApplyForce (World &world, BodyID id, Force2 force, Length2 point)
 Apply a force at a world point. More...
 
void ApplyTorque (World &world, BodyID id, Torque torque)
 Applies a torque. More...
 
void ApplyLinearImpulse (World &world, BodyID id, Momentum2 impulse, Length2 point)
 Applies an impulse at a point. More...
 
void ApplyAngularImpulse (World &world, BodyID id, AngularMomentum impulse)
 Applies an angular impulse. More...
 
BodyCounter GetAwakeCount (const World &world) noexcept
 Gets the count of awake bodies in the given world.
 
BodyCounter Awaken (World &world) noexcept
 Awakens all of the bodies in the given world. More...
 
void SetAccelerations (World &world, Acceleration acceleration) noexcept
 Sets the accelerations of all the world's bodies to the given value.
 
void SetAccelerations (World &world, LinearAcceleration2 acceleration) noexcept
 Sets the accelerations of all the world's bodies to the given value. More...
 
BodyID FindClosestBody (const World &world, Length2 location) noexcept
 Finds body in given world that's closest to the given location.
 
FixtureCounter GetFixtureCount (const World &world, BodyID id)
 Gets the count of fixtures associated with the identified body. More...
 
void SetTransform (World &world, BodyID id, Length2 location, Angle angle)
 Sets the position of the body's origin and rotation. More...
 
Length2 GetLocation (const World &world, BodyID id)
 Convenience function for getting just the location of the identified body. More...
 
Length2 GetWorldPoint (const World &world, BodyID id, const Length2 localPoint)
 Gets the world coordinates of a point given in coordinates relative to the body's origin. More...
 
UnitVec GetLocalVector (const World &world, BodyID body, const UnitVec uv)
 Convenience function for getting the local vector of the identified body. More...
 
Length2 GetLocalPoint (const World &world, BodyID body, const Length2 worldPoint)
 Gets a local point relative to the body's origin given a world point. More...
 
Position GetPosition (const World &world, BodyID id)
 Convenience function for getting the position of the identified body.
 
UnitVec GetWorldVector (const World &world, BodyID body, UnitVec localVector)
 Convenience function for getting a world vector of the identified body.
 
LinearVelocity2 GetLinearVelocity (const World &world, BodyID id)
 Gets the linear velocity of the center of mass of the identified body. More...
 
AngularVelocity GetAngularVelocity (const World &world, BodyID id)
 Gets the angular velocity. More...
 
bool Awaken (World &world, BodyID id)
 Awakens the body if it's asleep. More...
 
Mass GetMass (const World &world, BodyID id)
 Gets the mass of the body. More...
 
RotInertia GetRotInertia (const World &world, BodyID id)
 Gets the rotational inertia of the body. More...
 
RotInertia GetLocalRotInertia (const World &world, BodyID id)
 Gets the rotational inertia of the body about the local origin. More...
 
MassData GetMassData (const World &world, BodyID id)
 Gets the mass data of the body. More...
 
void ResetMassData (World &world, BodyID id)
 Resets the mass data properties. More...
 
void SetImpenetrable (World &world, BodyID id, bool value)
 Convenience function that sets/unsets the impenetrable status of the identified body. More...
 
void ApplyForceToCenter (World &world, BodyID id, Force2 force)
 Applies a force to the center of mass of the given body. More...
 
void SetForce (World &world, BodyID id, Force2 force, Length2 point) noexcept
 Sets the given amount of force at the given point to the given body. More...
 
void SetTorque (World &world, BodyID id, Torque torque) noexcept
 Sets the given amount of torque to the given body. More...
 
BodyCounter GetBodyCount (const World &world) noexcept
 Gets the body count in the given world. More...
 
void ClearForces (World &world) noexcept
 Clears forces. More...
 
template<class F >
void SetAccelerations (World &world, F fn)
 Sets the accelerations of all the world's bodies. More...
 
constexpr WorldConf GetDefaultWorldConf () noexcept
 Gets the default definitions value. More...
 
ContactCounter GetContactRange (const World &world) noexcept
 Gets the extent of the currently valid contact range. More...
 
SizedRange< std::vector< KeyedContactPtr >::const_iterator > GetContacts (const World &world) noexcept
 Gets the contacts recognized within the given world.
 
const ContactGetContact (const World &world, ContactID id)
 Gets the identified contact. More...
 
void SetContact (World &world, ContactID id, const Contact &value)
 Sets the identified contact's state. More...
 
bool IsTouching (const World &world, ContactID id)
 Is this contact touching? More...
 
bool IsAwake (const World &world, ContactID id)
 Gets the awake status of the specified contact. More...
 
void SetAwake (World &world, ContactID id)
 Sets awake the bodies of the fixtures of the given contact. More...
 
ChildCounter GetChildIndexA (const World &world, ContactID id)
 Get the child primitive index for fixture A. More...
 
ChildCounter GetChildIndexB (const World &world, ContactID id)
 Get the child primitive index for fixture B. More...
 
FixtureID GetFixtureA (const World &world, ContactID id)
 Gets fixture A of the identified contact. More...
 
FixtureID GetFixtureB (const World &world, ContactID id)
 Gets fixture B of the identified contact. More...
 
BodyID GetBodyA (const World &world, ContactID id)
 Gets the body-A of the identified contact if it has one. More...
 
BodyID GetBodyB (const World &world, ContactID id)
 Gets the body-B of the identified contact if it has one. More...
 
TimestepIters GetToiCount (const World &world, ContactID id)
 Gets the Time Of Impact (TOI) count. More...
 
bool NeedsFiltering (const World &world, ContactID id)
 Whether or not the contact needs filtering. More...
 
bool NeedsUpdating (const World &world, ContactID id)
 Whether or not the contact needs updating. More...
 
bool HasValidToi (const World &world, ContactID id)
 Whether or not the contact has a valid TOI. More...
 
Real GetToi (const World &world, ContactID id)
 Gets the time of impact (TOI) as a fraction. More...
 
Real GetFriction (const World &world, ContactID id)
 Gets the friction used with the identified contact. More...
 
Real GetRestitution (const World &world, ContactID id)
 Gets the restitution used with the identified contact. More...
 
void SetFriction (World &world, ContactID id, Real friction)
 Sets the friction value for the identified contact. More...
 
void SetRestitution (World &world, ContactID id, Real restitution)
 Sets the restitution value for the specified contact. More...
 
const ManifoldGetManifold (const World &world, ContactID id)
 Gets the manifold for the identified contact. More...
 
LinearVelocity GetTangentSpeed (const World &world, ContactID id)
 Gets the tangent speed of the identified contact. More...
 
void SetTangentSpeed (World &world, ContactID id, LinearVelocity value)
 Sets the desired tangent speed for a conveyor belt behavior. More...
 
bool IsEnabled (const World &world, ContactID id)
 Gets the enabled status of the identified contact. More...
 
void SetEnabled (World &world, ContactID id)
 Sets the enabled status of the identified contact. More...
 
void UnsetEnabled (World &world, ContactID id)
 Unsets the enabled status of the identified contact. More...
 
Real GetDefaultFriction (const World &world, ContactID id)
 Gets the default friction amount for the identified contact. More...
 
Real GetDefaultRestitution (const World &world, ContactID id)
 Gets the default restitution amount for the identified contact. More...
 
WorldManifold GetWorldManifold (const World &world, ContactID id)
 Gets the world manifold for the identified contact. More...
 
ContactCounter GetTouchingCount (const World &world) noexcept
 Gets the touching count for the given world.
 
void ResetFriction (World &world, ContactID id)
 Resets the friction mixture to the default value. More...
 
void ResetRestitution (World &world, ContactID id)
 Resets the restitution to the default value. More...
 
void SetEnabled (World &world, ContactID id, bool value)
 Convenience function for setting/unsetting the enabled status of the identified contact based on the value parameter. More...
 
ContactCounter GetContactCount (const World &world) noexcept
 Gets the count of contacts in the given world. More...
 
FixtureCounter GetFixtureRange (const World &world) noexcept
 Gets the extent of the currently valid fixture range. More...
 
FixtureCounter GetFixtureCount (const World &world) noexcept
 Gets the count of fixtures in the given world. More...
 
FixtureID CreateFixture (World &world, FixtureConf def=FixtureConf{}, bool resetMassData=true)
 Creates a fixture within the specified world. More...
 
FixtureID CreateFixture (World &world, BodyID id, const Shape &shape, FixtureConf def=FixtureConf{}, bool resetMassData=true)
 Creates a fixture within the specified world. More...
 
bool Destroy (World &world, FixtureID id, bool resetMassData=true)
 Destroys the identified fixture. More...
 
Filter GetFilterData (const World &world, FixtureID id)
 Gets the filter data for the identified fixture. More...
 
void SetFilterData (World &world, FixtureID id, const Filter &filter)
 Sets the contact filtering data. More...
 
BodyID GetBody (const World &world, FixtureID id)
 Gets the identifier of the body associated with the identified fixture. More...
 
Transformation GetTransformation (const World &world, FixtureID id)
 Gets the transformation associated with the given fixture. More...
 
const ShapeGetShape (const World &world, FixtureID id)
 Gets the shape associated with the identified fixture. More...
 
bool IsSensor (const World &world, FixtureID id)
 Is the specified fixture a sensor (non-solid)? More...
 
void SetSensor (World &world, FixtureID id, bool value)
 Sets whether the fixture is a sensor or not. More...
 
AreaDensity GetDensity (const World &world, FixtureID id)
 Gets the density of this fixture. More...
 
bool TestPoint (const World &world, FixtureID id, Length2 p)
 Tests a point for containment in a fixture. More...
 
template<typename T >
FixtureID CreateFixture (World &world, BodyID id, const T &shapeConf, FixtureConf def=FixtureConf{}, bool resetMassData=true)
 Creates a fixture within the specified world using a configuration of a shape. More...
 
Real GetFriction (const World &world, FixtureID id)
 Gets the coefficient of friction of the specified fixture. More...
 
Real GetRestitution (const World &world, FixtureID id)
 Gets the coefficient of restitution of the specified fixture. More...
 
MassData GetMassData (const World &world, FixtureID id)
 Gets the mass data for the identified fixture in the given world. More...
 
BodyCounter GetBodyRange (const WorldImpl &world) noexcept
 Gets the extent of the currently valid body range. More...
 
BodyID CreateBody (WorldImpl &world, const BodyConf &def=GetDefaultBodyConf())
 Creates a body with the given configuration within the given world.
 
const BodyGetBody (const WorldImpl &world, BodyID id)
 Gets the body configuration for the identified body. More...
 
void SetBody (WorldImpl &world, BodyID id, const Body &value)
 Sets the body state for the identified body. More...
 
void Destroy (WorldImpl &world, BodyID id)
 Destroys the identified body.
 
SizedRange< std::vector< std::pair< BodyID, JointID > >::const_iterator > GetJoints (const WorldImpl &world, BodyID id)
 Gets the range of all joints attached to this body. More...
 
SizedRange< WorldImpl::Fixtures::const_iterator > GetFixtures (const WorldImpl &world, BodyID id)
 Gets the range of all constant fixtures attached to the given body. More...
 
SizedRange< std::vector< KeyedContactPtr >::const_iterator > GetContacts (const WorldImpl &world, BodyID id)
 Gets the container of all contacts attached to this body. More...
 
ContactCounter GetContactRange (const WorldImpl &world) noexcept
 Gets the extent of the currently valid contact range. More...
 
const ContactGetContact (const WorldImpl &world, ContactID id)
 Gets the identified contact. More...
 
void SetContact (WorldImpl &world, ContactID id, const Contact &value)
 Sets the identified contact's state. More...
 
const ManifoldGetManifold (const WorldImpl &world, ContactID id)
 Gets the collision manifold for the identified contact.
 
FixtureCounter GetFixtureRange (const WorldImpl &world) noexcept
 Gets the extent of the currently valid fixture range. More...
 
FixtureID CreateFixture (WorldImpl &world, const FixtureConf &def)
 Creates a fixture per the given configuration. More...
 
const FixtureConfGetFixture (const WorldImpl &world, FixtureID id)
 Gets the identified fixture state. More...
 
void SetFixture (WorldImpl &world, FixtureID id, const FixtureConf &value)
 Sets the identified fixture's state. More...
 
bool Destroy (WorldImpl &world, FixtureID id)
 Destroys the identified fixture. More...
 
const std::vector< ContactCounter > & GetProxies (const WorldImpl &world, FixtureID id)
 Gets the dynamic tree leaves awaiting processing for the finding of new contacts.
 
ContactCounter GetProxy (const WorldImpl &world, FixtureID id, ChildCounter child)
 Gets the specified proxy of the identified fixture. More...
 
ChildCounter GetProxyCount (const WorldImpl &world, FixtureID id)
 Gets the count of proxies of the identified fixture. More...
 
JointCounter GetJointRange (const WorldImpl &world) noexcept
 Gets the extent of the currently valid joint range. More...
 
JointID CreateJoint (WorldImpl &world, const Joint &def)
 Creates a new joint.
 
void Destroy (WorldImpl &world, JointID id)
 Destroys the identified joint.
 
const JointGetJoint (const WorldImpl &world, JointID id)
 Gets the identified joint's value.
 
void SetJoint (WorldImpl &world, JointID id, const Joint &def)
 Sets the identified joint's new value.
 
std::unique_ptr< WorldImplCreateWorldImpl (const WorldConf &def)
 Creates a new world with the given configuration.
 
std::unique_ptr< WorldImplCreateWorldImpl (const WorldImpl &other)
 Creates a new world that's a copy of the given world.
 
void Clear (WorldImpl &world) noexcept
 Clears the given world.
 
void SetFixtureDestructionListener (WorldImpl &world, std::function< void(FixtureID)> listener) noexcept
 Registers a destruction listener for fixtures.
 
void SetJointDestructionListener (WorldImpl &world, std::function< void(JointID)> listener) noexcept
 Registers a destruction listener for joints.
 
void SetBeginContactListener (WorldImpl &world, std::function< void(ContactID)> listener) noexcept
 Registers a begin contact event listener.
 
void SetEndContactListener (WorldImpl &world, std::function< void(ContactID)> listener) noexcept
 Registers an end contact event listener.
 
void SetPreSolveContactListener (WorldImpl &world, std::function< void(ContactID, const Manifold &)> listener) noexcept
 Registers a pre-solve contact event listener.
 
void SetPostSolveContactListener (WorldImpl &world, std::function< void(ContactID, const ContactImpulsesList &, unsigned)> listener) noexcept
 Registers a post-solve contact event listener.
 
StepStats Step (WorldImpl &world, const StepConf &conf)
 Steps the given world the specified amount.
 
void ShiftOrigin (WorldImpl &world, Length2 newOrigin)
 Shifts the world origin. More...
 
SizedRange< std::vector< BodyID >::const_iterator > GetBodies (const WorldImpl &world) noexcept
 Gets the bodies of the specified world.
 
SizedRange< std::vector< BodyID >::const_iterator > GetBodiesForProxies (const WorldImpl &world) noexcept
 Gets the bodies-for-proxies range for this world. More...
 
SizedRange< std::vector< JointID >::const_iterator > GetJoints (const WorldImpl &world) noexcept
 Gets the joints of the specified world.
 
SizedRange< std::vector< KeyedContactPtr >::const_iterator > GetContacts (const WorldImpl &world) noexcept
 Gets the contacts of the specified world.
 
bool IsLocked (const WorldImpl &world) noexcept
 Is the world locked (in the middle of a time step).
 
bool IsStepComplete (const WorldImpl &world) noexcept
 Whether or not "step" is complete. More...
 
bool GetSubStepping (const WorldImpl &world) noexcept
 Gets whether or not sub-stepping is enabled. More...
 
void SetSubStepping (WorldImpl &world, bool value) noexcept
 Enables/disables single stepped continuous physics. More...
 
Length GetMinVertexRadius (const WorldImpl &world) noexcept
 Gets the minimum vertex radius that shapes in this world can be.
 
Length GetMaxVertexRadius (const WorldImpl &world) noexcept
 Gets the maximum vertex radius that shapes in this world can be.
 
Frequency GetInvDeltaTime (const WorldImpl &world) noexcept
 Gets the inverse delta time. More...
 
const DynamicTreeGetTree (const WorldImpl &world) noexcept
 Gets access to the broad-phase dynamic tree information.
 
SizedRange< std::vector< FixtureID >::const_iterator > GetFixturesForProxies (const WorldImpl &world) noexcept
 Gets the fixtures-for-proxies range for this world. More...
 
JointCounter GetJointRange (const World &world) noexcept
 Gets the extent of the currently valid joint range. More...
 
SizedRange< std::vector< JointID >::const_iterator > GetJoints (const World &world) noexcept
 Gets the joints of the specified world.
 
JointID CreateJoint (World &world, const Joint &def)
 Creates a new joint within the given world.
 
void Destroy (World &world, JointID id)
 Destroys the identified joint. More...
 
const JointGetJoint (const World &world, JointID id)
 Gets the value of the identified joint. More...
 
void SetJoint (World &world, JointID id, const Joint &def)
 Sets the value of the identified joint. More...
 
TypeID GetType (const World &world, JointID id)
 Gets the type of the joint. More...
 
bool GetCollideConnected (const World &world, JointID id)
 Gets collide connected for the specified joint. More...
 
BodyID GetBodyA (const World &world, JointID id)
 Gets the identifier of body-A of the identified joint. More...
 
BodyID GetBodyB (const World &world, JointID id)
 Gets the identifier of body-B of the identified joint. More...
 
Length2 GetLocalAnchorA (const World &world, JointID id)
 Get the anchor point on body-A in local coordinates. More...
 
Length2 GetLocalAnchorB (const World &world, JointID id)
 Get the anchor point on body-B in local coordinates. More...
 
Momentum2 GetLinearReaction (const World &world, JointID id)
 Gets the linear reaction on body-B at the joint anchor. More...
 
AngularMomentum GetAngularReaction (const World &world, JointID id)
 Get the angular reaction on body-B for the identified joint. More...
 
Angle GetReferenceAngle (const World &world, JointID id)
 Gets the reference-angle property of the identified joint if it has it. More...
 
void SetAwake (World &world, JointID id)
 Wakes up the joined bodies. More...
 
UnitVec GetLocalXAxisA (const World &world, JointID id)
 Gets the local-X-axis-A property of the identified joint if it has it. More...
 
UnitVec GetLocalYAxisA (const World &world, JointID id)
 Gets the local-Y-axis-A property of the identified joint if it has it. More...
 
AngularVelocity GetMotorSpeed (const World &world, JointID id)
 Gets the motor-speed property of the identied joint if it supports it. More...
 
void SetMotorSpeed (World &world, JointID id, AngularVelocity value)
 Sets the motor-speed property of the identied joint if it supports it. More...
 
AngularMomentum GetAngularMotorImpulse (const World &world, JointID id)
 Gets the angular motor impulse of the identified joint if it has this property. More...
 
RotInertia GetAngularMass (const World &world, JointID id)
 Gets the computed angular rotational inertia used by the joint. More...
 
Torque GetMaxMotorTorque (const World &world, JointID id)
 Gets the max motor torque. More...
 
void SetMaxMotorTorque (World &world, JointID id, Torque value)
 Sets the maximum motor torque. More...
 
Frequency GetFrequency (const World &world, JointID id)
 Gets the frequency of the identified joint if it has this property. More...
 
void SetFrequency (World &world, JointID id, Frequency value)
 Sets the frequency of the identified joint if it has this property. More...
 
AngularVelocity GetAngularVelocity (const World &world, JointID id)
 Gets the angular velocity of the identified joint if it has this property. More...
 
bool IsEnabled (const World &world, JointID id)
 Gets the enabled/disabled state of the joint. More...
 
JointCounter GetWorldIndex (const World &world, JointID id) noexcept
 Gets the world index of the given joint. More...
 
Length2 GetAnchorA (const World &world, JointID id)
 Get the anchor point on body-A in world coordinates. More...
 
Length2 GetAnchorB (const World &world, JointID id)
 Get the anchor point on body-B in world coordinates. More...
 
Real GetRatio (const World &world, JointID id)
 Gets the ratio property of the identified joint if it has it. More...
 
Length GetJointTranslation (const World &world, JointID id)
 Gets the current joint translation. More...
 
Angle GetAngle (const World &world, JointID id)
 Gets the angle property of the identified joint if it has it. More...
 
bool IsLimitEnabled (const World &world, JointID id)
 Gets whether the identified joint's limit is enabled. More...
 
void EnableLimit (World &world, JointID id, bool value)
 Sets whether the identified joint's limit is enabled or not. More...
 
bool IsMotorEnabled (const World &world, JointID id)
 Is the joint motor enabled? More...
 
void EnableMotor (World &world, JointID id, bool value)
 Enable/disable the joint motor. More...
 
Momentum GetLinearMotorImpulse (const World &world, JointID id)
 Gets the linear motor impulse of the identified joint if it supports that. More...
 
Length2 GetLinearOffset (const World &world, JointID id)
 Gets the target linear offset, in frame A. More...
 
void SetLinearOffset (World &world, JointID id, Length2 value)
 Sets the target linear offset, in frame A. More...
 
Angle GetAngularOffset (const World &world, JointID id)
 Gets the target angular offset. More...
 
void SetAngularOffset (World &world, JointID id, Angle value)
 Sets the target angular offset. More...
 
Length2 GetGroundAnchorA (const World &world, JointID id)
 Get the first ground anchor. More...
 
Length2 GetGroundAnchorB (const World &world, JointID id)
 Get the second ground anchor. More...
 
Length GetCurrentLengthA (const World &world, JointID id)
 Get the current length of the segment attached to body-A. More...
 
Length GetCurrentLengthB (const World &world, JointID id)
 Get the current length of the segment attached to body-B. More...
 
Length2 GetTarget (const World &world, JointID id)
 Gets the target point. More...
 
void SetTarget (World &world, JointID id, Length2 value)
 Sets the target point. More...
 
Angle GetAngularLowerLimit (const World &world, JointID id)
 Get the lower joint limit. More...
 
Angle GetAngularUpperLimit (const World &world, JointID id)
 Get the upper joint limit. More...
 
void SetAngularLimits (World &world, JointID id, Angle lower, Angle upper)
 Set the joint limits. More...
 
bool ShiftOrigin (World &world, JointID id, Length2 value)
 Shifts the origin of the identified joint. More...
 
Real GetDampingRatio (const World &world, JointID id)
 Gets the damping ratio associated with the identified joint if it has one. More...
 
Length GetLength (const World &world, JointID id)
 Gets the length associated with the identified joint if it has one. More...
 
LimitState GetLimitState (const World &world, JointID id)
 Gets the joint's limit state if it has one. More...
 
template<typename T >
JointID CreateJoint (World &world, const T &value)
 Creates a new joint from a configuration. More...
 
template<typename T >
void SetJoint (World &world, JointID id, const T &value)
 Sets a joint's value from a configuration. More...
 
Force GetMotorForce (const World &world, JointID id, Frequency inv_dt)
 Gets the current motor force for the given joint, given the inverse time step. More...
 
Torque GetMotorTorque (const World &world, JointID id, Frequency inv_dt)
 Gets the current motor torque for the given joint given the inverse time step. More...
 
JointCounter GetJointCount (const World &world) noexcept
 Gets the count of joints in the given world. More...
 
void SetFixtureDestructionListener (World &world, std::function< void(FixtureID)> listener) noexcept
 Sets the fixture destruction lister.
 
void SetJointDestructionListener (World &world, std::function< void(JointID)> listener) noexcept
 Sets the joint destruction lister.
 
void SetBeginContactListener (World &world, std::function< void(ContactID)> listener) noexcept
 Sets the begin-contact lister.
 
void SetEndContactListener (World &world, std::function< void(ContactID)> listener) noexcept
 Sets the end-contact lister.
 
void SetPreSolveContactListener (World &world, std::function< void(ContactID, const Manifold &)> listener) noexcept
 Sets the pre-solve-contact lister.
 
void SetPostSolveContactListener (World &world, std::function< void(ContactID, const ContactImpulsesList &, unsigned)> listener) noexcept
 Sets the post-solve-contact lister.
 
void Clear (World &world) noexcept
 Clears this world. More...
 
Length GetMinVertexRadius (const World &world) noexcept
 Gets the min vertex radius that shapes for the given world are allowed to be.
 
Length GetMaxVertexRadius (const World &world) noexcept
 Gets the max vertex radius that shapes for the given world are allowed to be.
 
StepStats Step (World &world, const StepConf &conf=StepConf{})
 Steps the given world the specified amount.
 
StepStats Step (World &world, Time delta, TimestepIters velocityIterations=8, TimestepIters positionIterations=3)
 Steps the world ahead by a given time amount. More...
 
bool GetSubStepping (const World &world) noexcept
 Gets whether or not sub-stepping is enabled. More...
 
void SetSubStepping (World &world, bool flag) noexcept
 Enables/disables single stepped continuous physics. More...
 
const DynamicTreeGetTree (const World &world) noexcept
 Gets the dynamic tree of the given world.
 
FixtureCounter GetShapeCount (const World &world) noexcept
 Gets the count of unique shapes in the given world.
 
void ShiftOrigin (World &world, Length2 newOrigin)
 Shifts the world origin. More...
 

Variables

constexpr auto Transform_identity
 Identity transformation value. More...
 
constexpr auto EarthlyGravity
 Earthly gravity in 2-dimensions. More...
 

Detailed Description

Name space for 2-dimensionally related PlayRho names.

Typedef Documentation

◆ AABB

2-Dimensional Axis Aligned Bounding Box.

Note
This data structure is 16-bytes large (on at least one 64-bit platform).

◆ ClipList

Clip list for ClipSegmentToLine.

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

◆ DynamicTreeRayCastCB

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

Ray cast callback function.

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

◆ MassData

Mass data alias for 2-D objects.

Note
This data structure is 16-bytes large (on at least one 64-bit platform).
Examples
Shape.cpp.

◆ QueryFixtureCallback

using playrho::d2::QueryFixtureCallback = typedef std::function<bool(FixtureID fixture, 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

◆ SimplexEdges

using playrho::d2::SimplexEdges = typedef ArrayList<SimplexEdge, MaxSimplexEdges, std::remove_const<decltype(MaxSimplexEdges)>::type>

Simplex edge collection.

Note
This data is 20 * 3 + 4 = 64-bytes large (on at least one 64-bit platform).

Enumeration Type Documentation

◆ LimitState

Limit state.

Note
Only used by joints that implement some notion of a limited range.
Enumerator
e_inactiveLimit 

Inactive limit.

e_atLowerLimit 

At-lower limit.

e_atUpperLimit 

At-upper limit.

e_equalLimits 

Equal limit.

Equal limit is used to indicate that a joint's upper and lower limits are approximately the same.

Function Documentation

◆ ApplyAngularImpulse() [1/2]

void 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 ApplyAngularImpulse().

◆ ApplyAngularImpulse() [2/2]

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

◆ ApplyForce()

void ApplyForce ( World world,
BodyID  id,
Force2  force,
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
std::out_of_rangeIf given an invalid body identifier.
Examples
WorldBody.cpp.

Referenced by ApplyForce().

◆ ApplyForceToCenter()

void ApplyForceToCenter ( World world,
BodyID  id,
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
std::out_of_rangeIf given an invalid body identifier.

◆ ApplyLinearImpulse() [1/2]

void ApplyLinearImpulse ( Body body,
Momentum2  impulse,
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 ApplyLinearImpulse().

◆ ApplyLinearImpulse() [2/2]

void ApplyLinearImpulse ( World world,
BodyID  id,
Momentum2  impulse,
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
std::out_of_rangeIf given an invalid body identifier.

◆ ApplyTorque()

void 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
std::out_of_rangeIf given an invalid body identifier.
Examples
WorldBody.cpp.

Referenced by ApplyTorque().

◆ Awaken() [1/3]

bool Awaken ( Body body)
inlinenoexcept

Awakens the body if it's asleep.

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

Referenced by Awaken().

◆ Awaken() [2/3]

BodyCounter Awaken ( World world)
noexcept

Awakens all of the bodies in the given world.

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

Returns
Sum total of calls to bodies' SetAwake method that returned true.

◆ Awaken() [3/3]

bool Awaken ( World world,
BodyID  id 
)
inline

Awakens the body if it's asleep.

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ CalcGravitationalAcceleration()

Acceleration CalcGravitationalAcceleration ( const World world,
BodyID  id 
)

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 undefined if the given edge list has zero edges.
Returns
"search direction" vector.

Referenced by Distance().

◆ Cap()

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

Caps velocity.

Enforces maximums on the given velocity.

Parameters
velocityVelocity to cap. Behavior is undefined if this value is invalid.
hTime elapsed to get velocity for. Behavior is undefined if this value is invalid.
confMovement configuration. This defines caps on linear and angular speeds.

Referenced by GetBodyConstraint().

◆ Clear()

void Clear ( World world)
noexcept

Clears this world.

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

◆ ClearForces()

void ClearForces ( World world)
inlinenoexcept

Clears forces.

Manually clear the force buffer on all bodies.

◆ ClipSegmentToLine()

ClipList playrho::d2::ClipSegmentToLine ( const ClipList vIn,
const UnitVec normal,
Length  offset,
ContactFeature::Index  indexA 
)

Clipping for contact manifolds.

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

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

◆ CollideShapes()

Manifold CollideShapes ( const DistanceProxy shapeA,
const Transformation xfA,
const DistanceProxy shapeB,
const Transformation xfB,
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.

Referenced by playrho::d2::WorldImpl::Update().

◆ ComputeAABB() [1/2]

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

Warning
Behavior is undefined if the given transformation is invalid.
Parameters
proxyDistance proxy for the child shape.
xfWorld transform of the shape.
Returns
AABB for the proxy shape or the default AABB if the proxy has a zero vertex count.

Referenced by ComputeAABB(), ComputeIntersectingAABB(), and playrho::d2::WorldImpl::Synchronize().

◆ ComputeAABB() [2/2]

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

Warning
Behavior is undefined if a given transformation is invalid.
Parameters
proxyDistance proxy for the child shape.
xfm0World transform 0 of the shape.
xfm1World transform 1 of the shape.
Returns
AABB for the proxy shape or the default AABB if the proxy has a zero vertex count.

◆ ComputeHeight()

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

Computes the height of the tree from a given node.

Warning
Behavior is undefined if the given index is not valid.
Parameters
treeTree to compute the height at the given node for.
indexID of node to compute height from.
Returns
0 unless the given index is to a branch node.

Referenced by ComputeHeight().

◆ ComputeIntersectingAABB()

AABB playrho::d2::ComputeIntersectingAABB ( const World world,
FixtureID  fA,
ChildCounter  iA,
FixtureID  fB,
ChildCounter  iB 
)
noexcept

Computes the intersecting AABB for the given pair of fixtures and indexes.

The intersecting AABB for the given pair of fixtures is the intersection of the AABB for child A of the shape of fixture A with the AABB for child B of the shape of fixture B.

Referenced by ComputeIntersectingAABB().

◆ ComputeMassData()

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

Referenced by CreateFixture(), Destroy(), DestroyFixtures(), ResetMassData(), and SetType().

◆ 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()

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

Creates a rigid body with the given configuration.

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

◆ CreateFixture() [1/4]

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

Creates a fixture within the specified world.

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

◆ CreateFixture() [2/4]

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

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

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

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

◆ CreateFixture() [3/4]

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

Creates a fixture within the specified world.

Exceptions
WrongStateif called while the world is "locked".
std::out_of_rangeIf given an invalid body identifier in the configuration.
See also
CreateFixture(World&, BodyID, const Shape&,FixtureConf,bool).
Examples
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 WorldFixture.cpp.

Referenced by CreateFixture().

◆ CreateFixture() [4/4]

FixtureID CreateFixture ( WorldImpl world,
const FixtureConf def 
)

Creates a fixture per the given configuration.

See also
Destroy(WorldImpl& world, FixtureID id).

◆ CreateJoint()

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.

◆ Destroy() [1/4]

void Destroy ( World world,
BodyID  id 
)

Destroys the identified body.

Exceptions
std::out_of_rangeIf given an invalid body identifier.
See also
CreateBody(World&, const BodyConf&).
Examples
RevoluteJoint.cpp, WorldBody.cpp, and WorldFixture.cpp.

◆ Destroy() [2/4]

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

Destroys the identified fixture.

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

◆ Destroy() [3/4]

void Destroy ( World world,
JointID  id 
)

Destroys the identified joint.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ Destroy() [4/4]

bool Destroy ( WorldImpl world,
FixtureID  id 
)

Destroys the identified fixture.

Exceptions
std::out_of_rangeIf given an invalid fixture identifier.
See also
CreateFixture(WorldImpl& world, const FixtureConf& def).

◆ DestroyFixtures()

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

Destroys fixtures of the identified body.

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

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

◆ Distance()

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

Determines the closest points between two shapes.

Note
Supports any combination of shapes.
On the first call, the Simplex::Cache.count should be set to 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 and the count of iterations it took to determine them. The iteration count will always be greater than zero unless DefaultMaxDistanceIters is zero.

Referenced by GetToiViaSat(), and TestOverlap().

◆ EnableLimit() [1/2]

void 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 EnableLimit().

◆ EnableLimit() [2/2]

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

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

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ EnableMotor() [1/2]

void 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 EnableMotor().

◆ EnableMotor() [2/2]

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

Enable/disable the joint motor.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ Evaluate()

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

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

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

Referenced by GetToiViaSat().

◆ FindMinSeparation()

LengthIndexPair playrho::d2::FindMinSeparation ( const SeparationScenario scenario,
const Transformation xfA,
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 GetToiViaSat().

◆ GetAABB()

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.

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

Referenced by operator==().

◆ GetAcceleration() [2/2]

Acceleration 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 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 GetCurrentLengthA(), and GetJointTranslation().

◆ GetAnchorB()

Length2 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 GetCurrentLengthB(), and GetJointTranslation().

◆ GetAngle() [1/3]

Angle GetAngle ( const Body body)
inlinenoexcept

Gets the body's angle.

Returns
Body's angle relative to its World.

◆ GetAngle() [2/3]

Angle 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/3]

Angle 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 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]

Frequency GetAngularDamping ( const Body body)
inlinenoexcept

Gets the angular damping of the body.

See also
SetAngularDamping(Body& body, NonNegative<Frequency> value).
Examples
Body.cpp, and World.cpp.

Referenced by GetAngularDamping(), GetBodyConf(), and operator==().

◆ GetAngularDamping() [2/2]

Frequency 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 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 GetAngularLowerLimit().

◆ GetAngularLowerLimit() [2/2]

Angle 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 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 GetAngularMass().

◆ GetAngularMass() [2/2]

RotInertia 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 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 GetAngularMotorImpulse(), and GetMotorTorque().

◆ GetAngularMotorImpulse() [2/2]

AngularMomentum 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 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 GetAngularOffset().

◆ GetAngularOffset() [2/2]

Angle GetAngularOffset ( const World world,
JointID  id 
)

Gets the target angular offset.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetAngularReaction()

AngularMomentum 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 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 GetAngularUpperLimit().

◆ GetAngularUpperLimit() [2/2]

Angle GetAngularUpperLimit ( const World world,
JointID  id 
)

Get the upper joint limit.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetAngularVelocity() [1/3]

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, and WorldBody.cpp.

Referenced by GetAngularVelocity(), GetBodyConf(), and SetVelocity().

◆ GetAngularVelocity() [2/3]

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

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

◆ GetBodiesForProxies()

SizedRange< std::vector< BodyID >::const_iterator > GetBodiesForProxies ( const WorldImpl world)
noexcept

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

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

See also
WorldImpl::Step.

◆ GetBody() [1/3]

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

Gets the body configuration for the identified body.

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

◆ GetBody() [2/3]

BodyID GetBody ( const World world,
FixtureID  id 
)

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

Exceptions
std::out_of_rangeIf given an invalid fixture identifier.

◆ GetBody() [3/3]

const Body & GetBody ( const WorldImpl world,
BodyID  id 
)

Gets the body configuration for the identified body.

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ GetBodyA() [1/2]

BodyID 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 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 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 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 GetBodyConf ( const Body body)
noexcept

Gets the body definition for the given body.

Parameters
bodyBody to get the BodyConf for.

◆ GetBodyCount()

BodyCounter GetBodyCount ( const World world)
inlinenoexcept

Gets the body count in the given world.

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

◆ GetBodyRange() [1/2]

BodyCounter GetBodyRange ( const World 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
WorldBody.cpp.

◆ GetBodyRange() [2/2]

BodyCounter GetBodyRange ( const WorldImpl 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.

◆ GetCentripetalForce()

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

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

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

Referenced by GetCentripetalForce().

◆ 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.
Note
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 playrho::d2::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 GetChildIndexA ( const World world,
ContactID  id 
)

Get the child primitive index for fixture A.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.

◆ GetChildIndexB()

ChildCounter GetChildIndexB ( const World world,
ContactID  id 
)

Get the child primitive index for fixture B.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.

◆ 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, and WheelJoint.cpp.

Referenced by playrho::d2::WorldImpl::CreateJoint(), GetCollideConnected(), playrho::d2::WorldImpl::Remove(), Set(), and playrho::d2::WorldImpl::SetJoint().

◆ GetCollideConnected() [2/2]

bool 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]

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

◆ GetContact() [2/2]

const Contact & GetContact ( const WorldImpl world,
ContactID  id 
)

Gets the identified contact.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.

◆ 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 GetContactRange ( const World 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
WorldContact.cpp.

◆ GetContactRange() [2/2]

ContactCounter GetContactRange ( const WorldImpl 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.

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

Referenced by playrho::d2::VelocityConstraint::GetPoint().

◆ GetContacts() [1/2]

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

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

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

Referenced by GetContactCount(), and GetContacts().

◆ GetContacts() [2/2]

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

Gets the container of all contacts attached to this body.

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

◆ GetCurrentLengthA()

Length 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 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 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 GetDampingRatio().

◆ GetDampingRatio() [2/2]

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

Referenced by GetShapeCount().

◆ GetDefaultFriction()

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

◆ GetDefaultRestitution()

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

◆ GetDefaultWorldConf()

constexpr WorldConf GetDefaultWorldConf ( )
constexprnoexcept

Gets the default definitions value.

Note
This method exists as a work-around for providing the World constructor a default value without otherwise getting a compiler error such as: "cannot use defaulted constructor of '<code>Conf</code>' within '<code>World</code>' outside of member functions because 'gravity' has an initializer"
Examples
World.cpp.

◆ GetDensity() [1/2]

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

Gets the density of the given shape.

Returns
Non-negative density (in mass per area).
Examples
Shape.cpp, and WorldFixture.cpp.

Referenced by ComputeMassData(), playrho::d2::WorldImpl::CreateFixture(), and GetDensity().

◆ GetDensity() [2/2]

AreaDensity GetDensity ( const World world,
FixtureID  id 
)

Gets the density of this fixture.

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

◆ GetEdge()

Length2 GetEdge ( const PolygonShapeConf shape,
VertexCounter  index 
)

Gets the identified edge of the given polygon shape.

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

Referenced by playrho::d2::PolygonShapeConf::Set().

◆ GetFilterData()

Filter GetFilterData ( const World world,
FixtureID  id 
)

Gets the filter data for the identified fixture.

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

◆ GetFixture()

const FixtureConf & GetFixture ( const WorldImpl world,
FixtureID  id 
)

Gets the identified fixture state.

Exceptions
std::out_of_rangeIf given an invalid fixture identifier.

◆ GetFixtureA()

FixtureID GetFixtureA ( const World world,
ContactID  id 
)

Gets fixture A of the identified contact.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.

◆ GetFixtureB()

FixtureID GetFixtureB ( const World world,
ContactID  id 
)

Gets fixture B of the identified contact.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.

◆ GetFixtureCount() [1/2]

FixtureCounter GetFixtureCount ( const World world)
noexcept

Gets the count of fixtures in the given world.

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

◆ GetFixtureCount() [2/2]

FixtureCounter GetFixtureCount ( const World world,
BodyID  id 
)
inline

Gets the count of fixtures associated with the identified body.

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

◆ GetFixtureRange() [1/2]

FixtureCounter GetFixtureRange ( const World world)
noexcept

Gets the extent of the currently valid fixture range.

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

◆ GetFixtureRange() [2/2]

FixtureCounter GetFixtureRange ( const WorldImpl world)
noexcept

Gets the extent of the currently valid fixture range.

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

◆ GetFixtures() [1/2]

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

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

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

Referenced by ComputeAABB(), DestroyFixtures(), and GetFixtureCount().

◆ GetFixtures() [2/2]

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

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

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ GetFixturesForProxies()

SizedRange< std::vector< FixtureID >::const_iterator > GetFixturesForProxies ( const WorldImpl world)
noexcept

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

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

See also
Step.

◆ GetFrequency() [1/2]

Frequency 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 GetFrequency().

◆ GetFrequency() [2/2]

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

auto GetFriction ( const Contact contact)
inlinenoexcept

Gets the coefficient of friction.

See also
SetFriction.

◆ GetFriction() [2/4]

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

Gets the coefficient of friction.

Returns
Value of 0 or higher.
Examples
Shape.cpp, WorldContact.cpp, and WorldFixture.cpp.

Referenced by GetDefaultFriction(), and GetFriction().

◆ GetFriction() [3/4]

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

Real GetFriction ( const World world,
FixtureID  id 
)
inline

Gets the coefficient of friction of the specified fixture.

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

◆ 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 playrho::d2::ChainShapeConf::Add(), CalcSearchDirection(), GetManifold(), GetSeparationScenario(), playrho::d2::VelocityConstraint::GetTangent(), playrho::d2::PolygonShapeConf::Set(), and playrho::d2::EdgeShapeConf::Set().

◆ GetGroundAnchorA() [1/2]

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

Referenced by GetCurrentLengthA(), and GetGroundAnchorA().

◆ GetGroundAnchorA() [2/2]

Length2 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 GetGroundAnchorB ( const Joint object)
Exceptions
std::invalid_argumentIf not supported for the given joint's type.
Examples
PrismaticJoint.cpp, and PulleyJoint.cpp.

Referenced by GetCurrentLengthB(), and GetGroundAnchorB().

◆ GetGroundAnchorB() [2/2]

Length2 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

◆ GetInvDeltaTime()

Frequency GetInvDeltaTime ( const WorldImpl world)
noexcept

Gets the inverse delta time.

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

See also
Step.

◆ GetInvMass() [1/2]

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
SetInvMass.
Examples
Body.cpp.

Referenced by ApplyForce(), ApplyForceToCenter(), GetInvMass(), GetMass(), operator==(), and SetForce().

◆ GetInvMass() [2/2]

InvMass 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]

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 ApplyForce(), ApplyTorque(), GetInvRotInertia(), GetRotInertia(), operator==(), SetForce(), and SetTorque().

◆ GetInvRotInertia() [2/2]

InvRotInertia 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()

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

Gets the value of the identified joint.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetJointCount()

JointCounter GetJointCount ( const World world)
inlinenoexcept

Gets the count of joints in the given world.

Returns
0 or higher.
Examples
World.cpp.

◆ GetJointRange() [1/2]

JointCounter GetJointRange ( const World 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.

◆ GetJointRange() [2/2]

JointCounter GetJointRange ( const WorldImpl 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.

◆ GetJoints() [1/2]

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

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

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

Referenced by GetJointCount(), and GetJoints().

◆ GetJoints() [2/2]

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

Gets the range of all joints attached to this body.

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ GetJointTranslation()

Length 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 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 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 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 GetLimitState().

◆ GetLimitState() [2/2]

LimitState 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 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]

Frequency GetLinearDamping ( const Body body)
inlinenoexcept

Gets the linear damping of the body.

See also
SetLinearDamping(Body& body, NonNegative<Frequency> value).
Examples
Body.cpp, and World.cpp.

Referenced by GetBodyConf(), GetLinearDamping(), and operator==().

◆ GetLinearDamping() [2/2]

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

◆ GetLinearMotorImpulse() [1/2]

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

Referenced by GetLinearMotorImpulse(), and GetMotorForce().

◆ GetLinearMotorImpulse() [2/2]

Momentum 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 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 GetLinearOffset().

◆ GetLinearOffset() [2/2]

Length2 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()

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

◆ GetLinearVelocity() [1/2]

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, and WorldBody.cpp.

Referenced by GetBodyConf(), GetCentripetalForce(), and SetVelocity().

◆ GetLinearVelocity() [2/2]

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.

◆ 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 GetLinearVelocityFromLocalPoint().

◆ GetLocalAnchorA()

Length2 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()

Length2 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 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 GetDistanceJointConf(), GetFrictionJointConf(), GetMotorJointConf(), GetPrismaticJointConf(), GetPulleyJointConf(), GetRevoluteJointConf(), GetWeldJointConf(), and GetWheelJointConf().

◆ GetLocalPoint() [2/2]

Length2 GetLocalPoint ( const World world,
BodyID  body,
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.
bodyIdentifier of body that the returned point should be relative to.
worldPointpoint in world coordinates.
Returns
the corresponding local point relative to the body's origin.
Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ GetLocalRotInertia() [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::SetInvRotInertia.

Referenced by 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 GetPrismaticJointConf(), and 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 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 GetGearJointConf(), GetJointTranslation(), GetLinearVelocity(), and GetLocalXAxisA().

◆ GetLocalXAxisA() [2/2]

UnitVec 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 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 GetLocalYAxisA().

◆ GetLocalYAxisA() [2/2]

UnitVec 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 fixtures when they experience collisions.
    Returns
    World location of the body's origin.
    See also
    GetAngle.

◆ 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/3]

Manifold playrho::d2::GetManifold ( bool  flipped,
const DistanceProxy shape0,
const Transformation xf0,
const VertexCounter  idx0,
const DistanceProxy shape1,
const Transformation xf1,
const 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.
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.
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.

Referenced by CollideShapes(), and GetWorldManifold().

◆ GetManifold() [2/3]

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

Computes manifolds for face-to-point collision.

< Center of circle in frame of polygon.

◆ GetManifold() [3/3]

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

Gets the manifold for the identified contact.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.

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

Referenced by CalcGravitationalAcceleration(), GetCentripetalForce(), GetForce(), GetLocalRotInertia(), and 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)
noexcept

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

Gets the mass data for the given shape configuration.

Returns
Mass data for this shape.

◆ GetMassData() [2/6]

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

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 GetMassData ( const World world,
FixtureID  id 
)
inline

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

Exceptions
std::out_of_rangeIf given an invalid fixture identifier.

◆ GetMassData() [5/6]

MassData playrho::d2::GetMassData ( Length  r,
NonNegative< AreaDensity density,
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.
Examples
Shape.cpp.

Referenced by ComputeMassData(), playrho::d2::ChainShapeConf::GetMassData(), and GetMassData().

◆ GetMassData() [6/6]

MassData playrho::d2::GetMassData ( Length  r,
NonNegative< AreaDensity density,
Length2  v0,
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

◆ GetMaxForce()

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

◆ GetMaxMotorTorque() [1/2]

Torque 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 GetMaxMotorTorque().

◆ GetMaxMotorTorque() [2/2]

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

◆ GetMaxSeparation() [2/3]

SeparationInfo playrho::d2::GetMaxSeparation ( const DistanceProxy proxy1,
Transformation  xf1,
const DistanceProxy proxy2,
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.

Referenced by CollideShapes().

◆ GetMaxSeparation() [3/3]

SeparationInfo playrho::d2::GetMaxSeparation ( const DistanceProxy proxy1,
Transformation  xf1,
const DistanceProxy proxy2,
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.

◆ GetMaxSeparation4x4()

SeparationInfo playrho::d2::GetMaxSeparation4x4 ( const DistanceProxy proxy1,
Transformation  xf1,
const DistanceProxy proxy2,
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.

Referenced by CollideShapes().

◆ GetMaxTorque()

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

◆ GetMotorSpeed() [1/2]

AngularVelocity 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 GetMotorSpeed().

◆ GetMotorSpeed() [2/2]

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

◆ GetNext()

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

Gets the next index of the given node.

Warning
Behavior is undefined if the given node is not an "unused" node.

◆ 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 method.
Returns
Contact normal (in world coordinates) if previously set, an invalid value otherwise.

Referenced by playrho::d2::VelocityConstraint::GetPoint().

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

Referenced by playrho::d2::WorldImpl::UpdateContactTOIs().

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

Warning
Behavior is undefined for an invalid AABB.
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().

◆ GetPosition()

constexpr Position GetPosition ( const Position  pos0,
const Position  pos1,
const Real  beta 
)
constexprnoexcept

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

Parameters
pos0Position at unit interval value of 0.
pos1Position at unit interval value of 1.
betaUnit interval (value between 0 and 1) of travel between 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.
Examples
PulleyJoint.cpp, and WorldBody.cpp.

Referenced by playrho::d2::Sweep::Advance0(), and GetTransformation().

◆ GetProxy()

ContactCounter GetProxy ( const WorldImpl world,
FixtureID  id,
ChildCounter  child 
)

Gets the specified proxy of the identified fixture.

Exceptions
std::out_of_rangeIf given an invalid fixture identifier.

◆ GetProxyCount()

ChildCounter GetProxyCount ( const WorldImpl world,
FixtureID  id 
)
inline

Gets the count of proxies of the identified fixture.

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

◆ GetRatio() [1/2]

Real 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 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 GetReferenceAngle ( const Joint object)

Gets the reference angle of the joint if it has one.

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

Referenced by GetAngle(), GetGearJointConf(), GetReferenceAngle(), InitVelocity(), and SolvePosition().

◆ GetReferenceAngle() [2/2]

Angle 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 ( 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

◆ GetRestitution() [1/3]

auto GetRestitution ( const Contact contact)
inlinenoexcept

Gets the coefficient of restitution.

See also
SetRestitution.

◆ GetRestitution() [2/3]

Real 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 GetRestitution ( const World world,
FixtureID  id 
)
inline

Gets the coefficient of restitution of the specified fixture.

Exceptions
std::out_of_rangeIf given an invalid fixture identifier.

◆ GetRevPerpendicular()

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

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

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

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

Referenced by CalcSearchDirection(), GetContactRelVelocity(), GetLinearVelocity(), GetLinearVelocityFromWorldPoint(), GetManifold(), GetMassData(), RayCast(), and SolveVelocity().

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

Referenced by GetLocalRotInertia(), and 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.

Warning
Behavior is undefined if given less than one index pair or more than three.
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.

Referenced by GetToiViaSat().

◆ GetShape()

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

Gets the shape associated with the identified fixture.

Exceptions
std::out_of_rangeIf given an invalid fixture identifier.

◆ GetSubStepping() [1/2]

bool GetSubStepping ( const World world)
noexcept

Gets whether or not sub-stepping is enabled.

See also
SetSubStepping, IsStepComplete.

◆ GetSubStepping() [2/2]

bool GetSubStepping ( const WorldImpl world)
noexcept

Gets whether or not sub-stepping is enabled.

See also
SetSubStepping, IsStepComplete.
Examples
World.cpp.

◆ GetSupportIndex()

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

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

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

Note
0 is returned for a given zero length direction vector.
Parameters
proxyDistance proxy object to find index in if a valid index exists for it.
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 Distance().

◆ GetSweep()

const Sweep & GetSweep ( const Body body)
inlinenoexcept

Gets the body's sweep.

See also
SetSweep(Body& body, const Sweep& value).

Referenced by operator==().

◆ GetTangentSpeed() [1/2]

auto GetTangentSpeed ( const Contact contact)
inlinenoexcept

Gets the desired tangent speed.

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

Referenced by GetTangentSpeed().

◆ GetTangentSpeed() [2/2]

LinearVelocity GetTangentSpeed ( const World world,
ContactID  id 
)

Gets the tangent speed of the identified contact.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.

◆ GetTarget() [1/2]

Length2 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, and TargetJoint.cpp.

Referenced by GetTarget().

◆ GetTarget() [2/2]

Length2 GetTarget ( const World world,
JointID  id 
)

Gets the target point.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ GetToi() [1/2]

Real GetToi ( const Contact contact)
inlinenoexcept

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

Note
This is only valid if a TOI has been set.
See also
void SetToi(Real toi).
Returns
Time of impact fraction in the range of 0 to 1 if set (where 1 means no actual impact in current time slot), otherwise undefined.
See also
HasValidToi

Referenced by GetToi().

◆ GetToi() [2/2]

Real GetToi ( const World world,
ContactID  id 
)

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

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

◆ GetToiCount()

TimestepIters GetToiCount ( const World world,
ContactID  id 
)

Gets the Time Of Impact (TOI) count.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.

◆ GetToiViaSat()

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

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

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

See also
https://en.wikipedia.org/wiki/Hyperplane_separation_theorem
Precondition
The given sweeps are both at the same alpha-0.
Warning
Behavior is undefined if sweeps are not at the same alpha-0.
Behavior is undefined if the configuration's tMax is not between 0 and 1 inclusive.
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}?

Referenced by playrho::d2::WorldImpl::UpdateContactTOIs().

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

Referenced by playrho::d2::WorldImpl::SetBody(), playrho::d2::WorldImpl::SolveReg(), and playrho::d2::WorldImpl::SolveToi().

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

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

◆ GetTransformation() [1/4]

Transformation GetTransformation ( const Body body)
inlinenoexcept

Gets the body's transformation.

See also
SetTransformation(Body& body, Transformation value).

◆ GetTransformation() [2/4]

Transformation playrho::d2::GetTransformation ( const Sweep sweep,
const 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/4]

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

◆ GetTransformation() [4/4]

Transformation GetTransformation ( const World world,
FixtureID  id 
)

Gets the transformation associated with the given fixture.

Warning
Behavior is undefined if the fixture doesn't have an associated body - i.e. behavior is undefined if the fixture has nullptr as its associated body.
Exceptions
std::out_of_rangeIf given an invalid fixture identifier.

◆ GetType() [1/4]

BodyType GetType ( const Body body)
inlinenoexcept

Gets the type of this body.

See also
SetType(Body&,BodyType).

◆ GetType() [2/4]

◆ GetType() [3/4]

BodyType GetType ( const World world,
BodyID  id 
)

Gets the type of the identified body.

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

◆ GetType() [4/4]

TypeID GetType ( const World world,
JointID  id 
)

Gets the type of the joint.

Exceptions
std::out_of_rangeIf given an invalid joint 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 GetBodyConf(), and operator==().

◆ GetUnitVector()

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

Gets the unit vector for the given value.

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

Referenced by playrho::d2::ChainShapeConf::Add(), CalcGravitationalAcceleration(), playrho::d2::ConvexHull::Get(), GetMassData(), GetSeparationScenario(), InitVelocity(), RayCast(), playrho::d2::PolygonShapeConf::Set(), playrho::d2::EdgeShapeConf::Set(), and SolveVelocity().

◆ GetVelocity() [1/3]

Velocity GetVelocity ( const Body body)
inlinenoexcept

◆ GetVelocity() [2/3]

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.

Warning
Behavior is undefined if the given elapsed time is an invalid value (like NaN).
Parameters
bodyBody to get the velocity for.
hTime elapsed to get velocity for. Behavior is undefined if this value is invalid.
Examples
Body.cpp, PulleyJoint.cpp, RevoluteJoint.cpp, and WorldBody.cpp.

Referenced by GetAngularVelocity(), GetLinearVelocity(), GetVelocity(), and operator==().

◆ GetVelocity() [3/3]

Velocity 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.
Note
This must be a non-negative value.
See also
UseVertexRadius
Exceptions
InvalidArgumentif the child index is not less than the child count.

◆ GetWorldCenter()

Length2 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 GetWorldIndex ( const World world,
const 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 GetWorldIndex ( const World 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 GetWorldManifold ( const Manifold manifold,
Transformation  xfA,
Length  radiusA,
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.
Examples
WorldContact.cpp.

Referenced by GetWorldManifold().

◆ GetWorldManifold() [2/3]

WorldManifold 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 GetWorldManifold ( const World world,
ContactID  id 
)

Gets the world manifold for the identified contact.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.

◆ 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 GetLinearVelocityFromLocalPoint(), and 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()

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.

◆ GetYAxis()

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

Gets the "Y-axis".

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

◆ HasValidToi() [1/2]

auto HasValidToi ( const Contact contact)
inlinenoexcept

Gets whether a TOI is set.

See also
GetToi.
Examples
WorldContact.cpp.

Referenced by HasValidToi().

◆ HasValidToi() [2/2]

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

◆ InitVelocity() [1/12]

void InitVelocity ( DistanceJointConf object,
std::vector< 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.
Examples
PulleyJoint.cpp, and TargetJoint.cpp.

◆ InitVelocity() [2/12]

void InitVelocity ( FrictionJointConf object,
std::vector< 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() [3/12]

void InitVelocity ( GearJointConf object,
std::vector< 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() [4/12]

void playrho::d2::InitVelocity ( Joint object,
std::vector< 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 InitVelocity ( MotorJointConf object,
std::vector< 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() [6/12]

void InitVelocity ( PrismaticJointConf object,
std::vector< 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
SolveVelocityConstraints.

◆ InitVelocity() [7/12]

void InitVelocity ( PulleyJointConf object,
std::vector< 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() [8/12]

void InitVelocity ( RevoluteJointConf object,
std::vector< 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
SolveVelocityConstraints.

◆ InitVelocity() [9/12]

void InitVelocity ( RopeJointConf object,
std::vector< 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() [10/12]

void InitVelocity ( TargetJointConf object,
std::vector< 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() [11/12]

void InitVelocity ( WeldJointConf object,
std::vector< 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() [12/12]

void InitVelocity ( WheelJointConf object,
std::vector< 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.

◆ 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 Distance(), GetGearJointConf(), GetLocalVector(), InverseTransform(), MulT(), and 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 GetLocalPoint(), GetManifold(), RayCast(), and 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.
Examples
World.cpp, and WorldBody.cpp.

Referenced by GetBodyConf(), playrho::d2::Body::SetAcceleration(), and playrho::d2::Body::SetUnderActiveTime().

◆ IsAccelerable() [2/2]

bool 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

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.
See also
SetAwake(Body&), UnsetAwake(Body&).
Examples
RevoluteJoint.cpp, WorldBody.cpp, and WorldContact.cpp.

Referenced by Awaken(), GetAwakeCount(), GetBodyConf(), IsAwake(), and playrho::d2::WorldImpl::SetBody().

◆ IsAwake() [2/3]

bool 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).
Warning
Being awake may or may not imply being speedable.
Returns
true if the body is awake.
Exceptions
std::out_of_rangeIf given an invalid body identifier.
See also
SetAwake, UnsetAwake.

◆ IsAwake() [3/3]

bool IsAwake ( const World world,
ContactID  id 
)

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

◆ IsEnabled() [1/4]

◆ IsEnabled() [2/4]

bool 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 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 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]

bool IsFixedRotation ( const Body body)
inlinenoexcept

Does this body have fixed rotation?

See also
SetFixedRotation(Body&, bool).
Examples
WorldBody.cpp.

Referenced by GetBodyConf(), IsFixedRotation(), and SetFixedRotation().

◆ IsFixedRotation() [2/2]

bool 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, and WorldBody.cpp.

Referenced by GetBodyConf(), IsImpenetrable(), playrho::d2::WorldImpl::SolveToi(), and playrho::d2::WorldImpl::UpdateContactTOIs().

◆ IsImpenetrable() [2/2]

bool 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::GetLeafData(), and playrho::d2::DynamicTree::SetLeafData().

◆ IsLimitEnabled() [1/2]

bool 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 IsLimitEnabled().

◆ IsLimitEnabled() [2/2]

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

◆ IsMassDataDirty()

bool 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 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 IsMotorEnabled().

◆ IsMotorEnabled() [2/2]

bool 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()

bool IsSensor ( const World world,
FixtureID  id 
)

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

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

◆ IsSleepingAllowed() [1/2]

bool IsSleepingAllowed ( const Body body)
inlinenoexcept

Gets whether or not this body allowed to sleep.

See also
SetSleepingAllowed(Body&).
Examples
World.cpp.

Referenced by GetBodyConf(), and IsSleepingAllowed().

◆ IsSleepingAllowed() [2/2]

bool 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
World.cpp, and WorldBody.cpp.

Referenced by Awaken(), playrho::d2::WorldImpl::RemoveUnspeedablesFromIslanded(), playrho::d2::Body::SetSleepingAllowed(), and playrho::d2::Body::SetVelocity().

◆ IsSpeedable() [2/2]

bool 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()

bool IsStepComplete ( const WorldImpl world)
noexcept

Whether or not "step" is complete.

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

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

◆ IsTouching()

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

◆ 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::FreeNode(), GetAABB(), playrho::d2::DynamicTree::GetAABB(), 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 GetMaxSeparation(), and GetMaxSeparation4x4().

◆ NeedsFiltering()

bool NeedsFiltering ( const World world,
ContactID  id 
)

Whether or not the contact needs filtering.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.

◆ NeedsUpdating()

bool NeedsUpdating ( const World world,
ContactID  id 
)

Whether or not the contact needs updating.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.

◆ operator!=()

bool operator!= ( const Manifold lhs,
const Manifold rhs 
)
noexcept

Manifold inequality operator.

Determines whether the two given manifolds are not equal.

◆ operator==()

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

◆ 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 playrho::d2::WorldImpl::FindNewContacts(), and Query().

◆ Query() [2/2]

void playrho::d2::Query ( const DynamicTree tree,
const AABB aabb,
QueryFixtureCallback  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.

◆ 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 ResetMassData ( World world,
BodyID  id 
)
inline

Resets the mass data properties.

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

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

Referenced by SetFixedRotation().

◆ 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/2]

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

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.

Referenced by GetGearJointConf(), GetJointTranslation(), GetLinearVelocity(), GetManifold(), GetMaxSeparation(), GetMaxSeparation4x4(), GetSeparationScenario(), GetTransformation(), GetWorldVector(), InitVelocity(), Mul(), RayCast(), SolvePosition(), Transform(), and playrho::d2::PolygonShapeConf::Transform().

◆ RotateAboutLocalPoint()

void RotateAboutLocalPoint ( World world,
BodyID  id,
Angle  amount,
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
std::out_of_rangeIf given an invalid body identifier.
Examples
WorldBody.cpp.

◆ RotateAboutWorldPoint()

void RotateAboutWorldPoint ( World world,
BodyID  id,
Angle  amount,
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
std::out_of_rangeIf given an invalid body identifier.
Examples
WorldBody.cpp.

Referenced by RotateAboutLocalPoint().

◆ SetAcceleration() [1/8]

void SetAcceleration ( Body body,
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
WorldBody.cpp.

Referenced by ApplyForce(), ApplyForceToCenter(), ApplyTorque(), SetAcceleration(), SetAccelerations(), SetForce(), and SetTorque().

◆ SetAcceleration() [2/8]

void SetAcceleration ( Body body,
AngularAcceleration  value 
)
inlinenoexcept

Sets the given angular acceleration of the given body.

See also
GetAcceleration(const Body& body).

◆ SetAcceleration() [3/8]

void SetAcceleration ( Body body,
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,
LinearAcceleration2  value 
)
inlinenoexcept

Sets the given linear acceleration of the given body.

See also
GetAcceleration(const Body& body).

◆ SetAcceleration() [5/8]

void SetAcceleration ( World world,
BodyID  id,
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
std::out_of_rangeIf given an invalid body identifier.
See also
GetAcceleration(const World& world, BodyID id).

◆ SetAcceleration() [6/8]

void 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
std::out_of_rangeIf given an invalid body identifier.
See also
GetAcceleration(const World& world, BodyID id).

◆ SetAcceleration() [7/8]

void SetAcceleration ( World world,
BodyID  id,
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
std::out_of_rangeIf given an invalid body identifier.
See also
GetAcceleration(const World& world, BodyID id).

◆ SetAcceleration() [8/8]

void SetAcceleration ( World world,
BodyID  id,
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
std::out_of_rangeIf given an invalid body identifier.
See also
GetAcceleration(const World& world, BodyID id).

◆ SetAccelerations() [1/2]

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

Sets the accelerations of all the world's bodies.

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

◆ SetAccelerations() [2/2]

void SetAccelerations ( World world,
LinearAcceleration2  acceleration 
)
noexcept

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

Note
This will leave the angular acceleration alone.

◆ SetAngle()

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

Sets the body's angular orientation.

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

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

◆ 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 SetAngularDamping().

◆ SetAngularDamping() [2/2]

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

Sets the angular damping of the body.

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ SetAngularLimits() [1/2]

void 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 SetAngularLimits().

◆ SetAngularLimits() [2/2]

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

Set the joint limits.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ SetAngularOffset() [1/2]

void 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 SetAngularOffset().

◆ SetAngularOffset() [2/2]

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

Sets the target angular offset.

Exceptions
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 method has no effect otherwise.

Postcondition
If this body is a "speedable" body, then this body's IsAwake method returns true.
If this body is a "speedable" body, then this body's GetUnderActiveTime method returns zero.
See also
IsAwake(const Body&), UnsetAwake(Body&).
Examples
RevoluteJoint.cpp, WorldBody.cpp, and WorldContact.cpp.

Referenced by Awaken(), and SetAwake().

◆ SetAwake() [2/4]

void SetAwake ( World world,
BodyID  id 
)

Wakes up the identified body.

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

◆ SetAwake() [3/4]

void SetAwake ( World world,
ContactID  id 
)

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

Exceptions
std::out_of_rangeIf given an invalid contact identifier.

◆ SetAwake() [4/4]

void SetAwake ( World world,
JointID  id 
)

Wakes up the joined bodies.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ SetBody() [1/2]

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

Sets the body state for the identified body.

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

Referenced by ApplyAngularImpulse(), and ApplyLinearImpulse().

◆ SetBody() [2/2]

void SetBody ( WorldImpl world,
BodyID  id,
const Body value 
)

Sets the body state for the identified body.

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ SetContact() [1/2]

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

Sets the identified contact's state.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.

Referenced by SetEnabled(), SetFriction(), SetRestitution(), SetTangentSpeed(), and UnsetEnabled().

◆ SetContact() [2/2]

void SetContact ( WorldImpl world,
ContactID  id,
const Contact value 
)

Sets the identified contact's state.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.

◆ SetEnabled() [1/6]

void SetEnabled ( Body body)
inlinenoexcept

Sets the enabled state.

See also
IsEnabled(const Body&), UnsetEnabled(Body&).
Examples
WorldBody.cpp, and WorldContact.cpp.

Referenced by SetEnabled().

◆ SetEnabled() [2/6]

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

void playrho::d2::SetEnabled ( Contact contact)
inlinenoexcept

Enables the identified contact.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.

◆ SetEnabled() [4/6]

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

void SetEnabled ( World world,
ContactID  id 
)

Sets the enabled status of the identified contact.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.

◆ SetEnabled() [6/6]

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

◆ SetFilterData()

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

Sets the contact filtering data.

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

◆ SetFixedRotation() [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 SetFixedRotation().

◆ SetFixedRotation() [2/2]

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

Sets this body to have fixed rotation.

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

◆ SetFixture()

void SetFixture ( WorldImpl world,
FixtureID  id,
const FixtureConf value 
)

Sets the identified fixture's state.

Exceptions
std::out_of_rangeIf given an invalid fixture identifier.

◆ SetForce()

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

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

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ SetFrequency() [1/2]

void 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 SetFrequency ( World world,
JointID  id,
Frequency  value 
)

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

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ SetFriction() [1/2]

void SetFriction ( Contact contact,
Real  value 
)
inlinenoexcept

Sets the friction value for the identified contact.

Overrides the default friction mixture.

Note
This value persists until set or reset.
Warning
Behavior is undefined if given a negative friction value.
Parameters
contactThe contact whose friction should be set.
valueCo-efficient of friction value of zero or greater.
Exceptions
std::out_of_rangeIf given an invalid contact identifier.
See also
GetFriction.
Examples
WorldContact.cpp.

Referenced by ResetFriction(), and SetFriction().

◆ SetFriction() [2/2]

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

Sets the friction value for the identified contact.

Overrides the default friction mixture.

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

◆ SetImpenetrable() [1/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.

Referenced by SetImpenetrable().

◆ SetImpenetrable() [2/3]

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

◆ SetJoint() [1/2]

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

Sets the value of the identified joint.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ SetJoint() [2/2]

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

Sets a joint's value from a configuration.

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

◆ 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 SetLinearDamping().

◆ SetLinearDamping() [2/2]

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

Sets the linear damping of the body.

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ SetLinearLimits()

void 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 SetLinearOffset ( Joint object,
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 SetLinearOffset().

◆ SetLinearOffset() [2/2]

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

Sets the target linear offset, in frame A.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ SetLocation()

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

Sets the body's location.

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

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

◆ SetMassData()

void 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
std::out_of_rangeIf given an invalid body identifier.
Examples
WorldBody.cpp.

Referenced by CreateFixture(), Destroy(), DestroyFixtures(), ResetMassData(), and SetType().

◆ SetMaxMotorForce()

void 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 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 SetMaxMotorTorque().

◆ SetMaxMotorTorque() [2/2]

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

Sets the maximum motor torque.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ SetMotorSpeed() [1/2]

void 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 SetMotorSpeed().

◆ SetMotorSpeed() [2/2]

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

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

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

◆ SetRestitution() [1/2]

void SetRestitution ( Contact contact,
Real  value 
)
inline

Sets the restitution value for the identified contact.

This override the default restitution mixture.

Note
You can call this in "pre-solve" listeners.
The value persists until you set or reset.
Exceptions
std::out_of_rangeIf given an invalid contact identifier.
See also
GetRestitution.
Examples
WorldContact.cpp.

Referenced by ResetRestitution(), and SetRestitution().

◆ SetRestitution() [2/2]

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

◆ SetSensor()

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

Sets whether the fixture is a sensor or not.

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

◆ 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 SetSleepingAllowed().

◆ SetSleepingAllowed() [2/2]

void SetSleepingAllowed ( World world,
BodyID  ,
bool  value 
)

Sets whether the identified body is allowed to sleep.

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ SetSubStepping() [1/2]

void SetSubStepping ( World world,
bool  flag 
)
noexcept

Enables/disables single stepped continuous physics.

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

◆ SetSubStepping() [2/2]

void SetSubStepping ( WorldImpl world,
bool  value 
)
noexcept

Enables/disables single stepped continuous physics.

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

◆ SetSweep()

void SetSweep ( Body body,
const Sweep value 
)
inlinenoexcept

Sets the sweep value of the given body.

See also
GetSweep(const Body& body).

Referenced by SetTransformation().

◆ SetTangentSpeed() [1/2]

void SetTangentSpeed ( Contact contact,
LinearVelocity  value 
)
inlinenoexcept

Sets the desired tangent speed for a conveyor belt behavior.

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

Referenced by SetTangentSpeed().

◆ SetTangentSpeed() [2/2]

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

◆ SetTarget() [1/2]

void SetTarget ( Joint object,
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.

Referenced by SetTarget().

◆ SetTarget() [2/2]

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

Sets the target point.

Exceptions
std::out_of_rangeIf given an invalid joint identifier.

◆ SetTorque()

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

Sets the given amount of torque to the given body.

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ SetTransform()

void SetTransform ( World world,
BodyID  id,
Length2  location,
Angle  angle 
)
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. Behavior is undefined if value is invalid.
angleValid world rotation. Behavior is undefined if value is invalid.
Exceptions
std::out_of_rangeIf given an invalid body identifier.
Examples
WorldBody.cpp.

Referenced by RotateAboutWorldPoint(), SetAngle(), and SetLocation().

◆ SetTransformation() [1/2]

void SetTransformation ( Body body,
Transformation  value 
)
inlinenoexcept

Sets the body's transformation.

Note
This sets what GetLocation returns.
See also
GetTransformation(const Body& body).
Examples
WorldBody.cpp.

Referenced by SetTransform(), and SetTransformation().

◆ SetTransformation() [2/2]

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

Sets the transformation of the body.

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

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

◆ SetType() [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 SetType().

◆ SetType() [2/2]

void 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 method is called while the world is locked.
std::out_of_rangeIf given an invalid body identifier.
See also
GetType(const World& world, BodyID id)

◆ SetVelocity() [1/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 Velocity value 
)
inlinenoexcept

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

Note
This method does nothing if this body is not speedable.
A non-zero velocity will awaken this body.
See also
GetVelocity(const Body& body), SetAwake, SetUnderActiveTime.
Examples
WorldBody.cpp.

Referenced by SetVelocity().

◆ SetVelocity() [3/6]

void SetVelocity ( Body body,
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() [4/6]

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

Sets the velocity of the identified body.

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ SetVelocity() [5/6]

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

Sets the velocity of the identified body.

Exceptions
std::out_of_rangeIf given an invalid body identifier.

◆ SetVelocity() [6/6]

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

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

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

◆ ShiftOrigin() [1/4]

bool playrho::d2::ShiftOrigin ( Joint object,
Length2  value 
)
noexcept

Shifts the origin for any points stored in world coordinates.

Returns
true if shift done, false otherwise.

◆ ShiftOrigin() [2/4]

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

Shifts the origin of the identified joint.

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

◆ ShiftOrigin() [3/4]

void ShiftOrigin ( World world,
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 method is called while the world is locked.

◆ ShiftOrigin() [4/4]

void ShiftOrigin ( WorldImpl world,
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 method is called while the world is locked.

◆ ShouldCollide()

bool ShouldCollide ( const FixtureConf fixtureA,
const FixtureConf fixtureB 
)
inlinenoexcept

Whether contact calculations should be performed between the two fixtures.

Returns
true if contact calculations should be performed between these two fixtures; false otherwise.

Referenced by playrho::d2::WorldImpl::Add(), and playrho::d2::WorldImpl::DestroyContacts().

◆ size()

std::size_t playrho::d2::size ( const DynamicTree tree)
inlinenoexcept

Gets the "size" of the given tree.

Note
Size in this context is defined as the leaf count.
This provides ancillary support for the container named requirement's size method.
See also
DynamicTree::GetLeafCount()
https://en.cppreference.com/w/cpp/named_req/Container
Examples
World.cpp, WorldBody.cpp, and WorldFixture.cpp.

Referenced by playrho::d2::WorldImpl::Add(), playrho::d2::WorldImpl::AddToIsland(), CalcSearchDirection(), ClipSegmentToLine(), playrho::d2::WorldImpl::CreateBody(), playrho::d2::WorldImpl::CreateFixture(), playrho::d2::WorldImpl::CreateJoint(), playrho::d2::WorldImpl::DestroyContacts(), Distance(), FindLowestRightMostVertex(), playrho::d2::WorldImpl::GetBodies(), playrho::d2::WorldImpl::GetBodiesForProxies(), GetBodyCount(), GetChildCount(), GetContactCount(), playrho::d2::WorldImpl::GetContacts(), GetConvexHullAsVector(), playrho::d2::ConvexHull::GetDistanceProxy(), GetFixtureCount(), playrho::d2::WorldImpl::GetFixtures(), playrho::d2::WorldImpl::GetFixturesForProxies(), GetIndexPairs(), GetJointCount(), playrho::d2::WorldImpl::GetJoints(), GetManifold(), GetMassData(), playrho::d2::PolygonShapeConf::GetNormals(), GetShapeCount(), playrho::d2::ChainShapeConf::GetVertexCount(), playrho::d2::PolygonShapeConf::GetVertexCount(), playrho::d2::PolygonShapeConf::GetVertices(), GetWitnessPoints(), playrho::d2::PolygonShapeConf::Set(), playrho::d2::ChainShapeConf::Set(), playrho::d2::WorldImpl::SolveReg(), playrho::d2::WorldImpl::UpdateContacts(), playrho::d2::PolygonShapeConf::UseVertices(), and Validate().

◆ SolvePosition() [1/12]

bool SolvePosition ( const DistanceJointConf object,
std::vector< BodyConstraint > &  bodies,
const ConstraintSolverConf conf 
)

Solves the position constraint.

Returns
true if the position errors are within tolerance.
Examples
PulleyJoint.cpp, and TargetJoint.cpp.

◆ SolvePosition() [2/12]

bool SolvePosition ( const FrictionJointConf object,
std::vector< BodyConstraint > &  bodies,
const ConstraintSolverConf conf 
)

Solves the position constraint.

Returns
true if the position errors are within tolerance.

◆ SolvePosition() [3/12]

bool SolvePosition ( const GearJointConf object,
std::vector< BodyConstraint > &  bodies,
const ConstraintSolverConf conf 
)

Solves the position constraint.

Returns
true if the position errors are within tolerance.

◆ SolvePosition() [4/12]

bool playrho::d2::SolvePosition ( const Joint object,
std::vector< BodyConstraint > &  bodies,
const ConstraintSolverConf conf 
)

Solves the position constraint.

Returns
true if the position errors are within tolerance.

◆ SolvePosition() [5/12]

bool SolvePosition ( const MotorJointConf object,
std::vector< BodyConstraint > &  bodies,
const ConstraintSolverConf conf 
)

Solves the position constraint.

Returns
true if the position errors are within tolerance.

◆ SolvePosition() [6/12]

bool SolvePosition ( const PrismaticJointConf object,
std::vector< BodyConstraint > &  bodies,
const ConstraintSolverConf conf 
)

Solves the position constraint.

Returns
true if the position errors are within tolerance.

◆ SolvePosition() [7/12]

bool SolvePosition ( const PulleyJointConf object,
std::vector< BodyConstraint > &  bodies,
const ConstraintSolverConf conf 
)

Solves the position constraint.

Returns
true if the position errors are within tolerance.

◆ SolvePosition() [8/12]

bool SolvePosition ( const RevoluteJointConf object,
std::vector< BodyConstraint > &  bodies,
const ConstraintSolverConf conf 
)

Solves the position constraint.

Returns
true if the position errors are within tolerance.

◆ SolvePosition() [9/12]

bool SolvePosition ( const RopeJointConf object,
std::vector< BodyConstraint > &  bodies,
const ConstraintSolverConf conf 
)

Solves the position constraint.

Returns
true if the position errors are within tolerance.

◆ SolvePosition() [10/12]

bool SolvePosition ( const TargetJointConf object,
std::vector< BodyConstraint > &  bodies,
const ConstraintSolverConf conf 
)

Solves the position constraint.

Returns
true if the position errors are within tolerance.

◆ SolvePosition() [11/12]

bool SolvePosition ( const WeldJointConf object,
std::vector< BodyConstraint > &  bodies,
const ConstraintSolverConf conf 
)

Solves the position constraint.

Returns
true if the position errors are within tolerance.

◆ SolvePosition() [12/12]

bool SolvePosition ( const WheelJointConf object,
std::vector< BodyConstraint > &  bodies,
const ConstraintSolverConf conf 
)

Solves the position constraint.

Returns
true if the position errors are within tolerance.

◆ SolveVelocity() [1/12]

bool SolveVelocity ( DistanceJointConf object,
std::vector< BodyConstraint > &  bodies,
const StepConf step 
)

Solves velocity constraint.

Precondition
InitVelocity has been called.
See also
InitVelocity.
Returns
true if velocity is "solved", false otherwise.
Examples
PulleyJoint.cpp, and TargetJoint.cpp.

◆ SolveVelocity() [2/12]

bool SolveVelocity ( FrictionJointConf object,
std::vector< 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() [3/12]

bool SolveVelocity ( GearJointConf object,
std::vector< 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() [4/12]

bool playrho::d2::SolveVelocity ( Joint object,
std::vector< 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 SolveVelocity ( MotorJointConf object,
std::vector< 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() [6/12]

bool SolveVelocity ( PrismaticJointConf object,
std::vector< 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() [7/12]

bool SolveVelocity ( PulleyJointConf object,
std::vector< 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() [8/12]

bool SolveVelocity ( RevoluteJointConf object,
std::vector< 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() [9/12]

bool SolveVelocity ( RopeJointConf object,
std::vector< 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() [10/12]

bool SolveVelocity ( TargetJointConf object,
std::vector< 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() [11/12]

bool SolveVelocity ( WeldJointConf object,
std::vector< BodyConstraint > &  bodies,
const StepConf  
)

Solves velocity constraint.

Precondition
InitVelocity has been called.
See also
InitVelocity.
Returns
true if velocity is "solved", false otherwise.

◆ SolveVelocity() [12/12]

bool SolveVelocity ( WheelJointConf object,
std::vector< BodyConstraint > &  bodies,
const StepConf step 
)

Solves velocity constraint.

Precondition
InitVelocity has been called.
See also
InitVelocity.
Returns
true if velocity is "solved", false otherwise.

◆ Step()

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

Steps the world ahead by a given time amount.

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

Note
While body velocities are updated accordingly (per the sum of forces acting on them), body positions (barring any collisions) are updated as if they had moved the entire time step at those resulting velocities. In other words, a body initially at p0 going v0 fast with a sum acceleration of a, after time t and barring any collisions, will have a new velocity (v1) of v0 + (a * t) and a new position (p1) of p0 + v1 * t.
Warning
Varying the time step may lead to non-physical behaviors.
Postcondition
Static bodies are unmoved.
Kinetic bodies are moved based on their previous velocities.
Dynamic bodies are moved based on their previous velocities, gravity, applied forces, applied impulses, masses, damping, and the restitution and friction values of their fixtures when they experience collisions.
Parameters
worldWorld to step.
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.

Referenced by playrho::d2::WorldImpl::DestroyContacts(), Query(), RayCast(), TestOverlap(), and playrho::d2::WorldImpl::Update().

◆ Transform() [1/7]

void playrho::d2::Transform ( ChainShapeConf arg,
const Mat22 m 
)
inlinenoexcept

◆ Transform() [2/7]

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.

◆ Transform() [3/7]

void playrho::d2::Transform ( DiskShapeConf arg,
const Mat22 m 
)
inlinenoexcept

Transforms the given shape configuration's vertices by the given transformation matrix.

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

◆ Transform() [4/7]

void playrho::d2::Transform ( EdgeShapeConf arg,
const Mat22 m 
)
inlinenoexcept

Transforms the given shape configuration's vertices by the given transformation matrix.

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

◆ Transform() [5/7]

void playrho::d2::Transform ( MultiShapeConf arg,
const Mat22 m 
)
inlinenoexcept

Transforms the given multi shape configuration by the given transformation matrix.

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

◆ Transform() [6/7]

void playrho::d2::Transform ( PolygonShapeConf arg,
const Mat22 m 
)
inlinenoexcept

Transforms the given polygon configuration's vertices by the given transformation matrix.

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

◆ Transform() [7/7]

void playrho::d2::Transform ( Shape shape,
const Mat22 m 
)

Transforms all of the given shape's vertices by the given transformation matrix.

See also
https://en.wikipedia.org/wiki/Transformation_matrix
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.

◆ TypeCast() [1/7]

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

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/

◆ TypeCast() [3/7]

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

template<typename T >
std::add_pointer_t< std::add_const_t< T > > playrho::d2::TypeCast ( const Shape value)
inlinenoexcept

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&)
Examples
DistanceJoint.cpp, Joint.cpp, and Shape.cpp.

◆ TypeCast() [5/7]

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

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

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/

◆ 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
This body's IsAwake method returns false.
This body's GetUnderActiveTime method returns zero.
This body's GetVelocity method returns zero linear and zero angular speed.
See also
IsAwake(const Body&), SetAwake(Body&).
Examples
RevoluteJoint.cpp, WorldBody.cpp, and WorldContact.cpp.

Referenced by UnsetAwake().

◆ UnsetAwake() [2/2]

void UnsetAwake ( World world,
BodyID  id 
)

Sleeps the identified body.

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

◆ UnsetEnabled() [1/3]

void UnsetEnabled ( Body body)
inlinenoexcept

Unsets the enabled state.

See also
IsEnabled(const Body&), SetEnabled(Body&).
Examples
WorldContact.cpp.

Referenced by SetEnabled(), and UnsetEnabled().

◆ UnsetEnabled() [2/3]

void playrho::d2::UnsetEnabled ( Contact contact)
inlinenoexcept

Disables the identified contact.

Exceptions
std::out_of_rangeIf given an invalid contact identifier.

◆ UnsetEnabled() [3/3]

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

Referenced by SetImpenetrable(), and UnsetImpenetrable().

◆ UnsetImpenetrable() [2/2]

void UnsetImpenetrable ( World world,
BodyID  id 
)

Unsets the impenetrable status of the identified body.

Exceptions
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
constexpr
Initial value:

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.

◆ Transform_identity

constexpr auto playrho::d2::Transform_identity
constexpr
Initial value:
= Transformation{
Length2{0_m, 0_m}, UnitVec::GetRight()
}

Identity transformation value.

playrho::LinearAcceleration2
Vector2< LinearAcceleration > LinearAcceleration2
2-element vector of linear acceleration (LinearAcceleration) quantities.
Definition: Vector2.hpp:51
playrho::EarthlyLinearAcceleration
constexpr auto EarthlyLinearAcceleration
Earthly gravity.
Definition: Units.hpp:844
playrho::Length2
Vector2< Length > Length2
2-element vector of Length quantities.
Definition: Vector2.hpp:43