Reference
-
class Application
Public Functions
-
Application()
-
~Application()
-
void setName(const char *name)
-
template<std::derived_from<Scene> S, class ...Args>
inline void registerScene(const char *name, Args&&... args)
-
void run()
-
void close()
Private Members
-
GLFWwindow *window_ = nullptr
Private Static Functions
-
static void frameBufferResizeCallback(GLFWwindow *window, int w, int h)
-
static void windowResizeCallback(GLFWwindow *window, int w, int h)
-
static void keypressCallback(GLFWwindow *window, int key, int scancode, int action, int modifiers)
-
static void mouseMoveCallback(GLFWwindow *window, double x, double y)
-
static void mousePressCallback(GLFWwindow *window, int button, int action, int mods)
-
static void mouseScrollCallback(GLFWwindow *window, double x, double y)
-
Application()
-
struct Bias
-
class Block
-
class Bodies
-
Public Functions
Friends
- friend class Island
- friend class Constraint
-
class Body : public simu::PhysicsObject
Subclassed by simu::VisibleBody
Public Types
-
typedef PhysicsObject::PhysicsAlloc Alloc
Public Functions
-
inline Body(const BodyDescriptor &descriptor)
Constructs a Body.
-
inline ~Body() override
-
Collider *addCollider(const ColliderDescriptor &descriptor)
-
inline void applyForce(Vec2 force, float dt, Vec2 whereFromCentroid = Vec2{0, 0})
Applies a force for some time on an object.
whereFromCentroid does not need to lie inside the Body’s world space geometry.
-
inline void applyImpulse(Vec2 impulse, Vec2 whereFromCentroid = Vec2{0, 0})
Applies an impulse on an object.
whereFromCentroid does not need to lie inside the Body’s world space geometry.
-
inline void setAngularVelocity(float angularVelocity)
Change the Body’s angularVelocity to angularVelocity in radians/s.
-
inline Vec2 position() const
The Body’s world space position.
This is an offset of the Body’s local space geometry
-
inline float orientation() const
The Body’s world space orientation in radians.
The orientation rotates the Body’s local space geometry around its centroid
-
inline Transform toWorldSpace() const
Transformation matrix to convert from the Body’s local space to world space.
-
inline Transform toLocalSpace() const
Transformation matrix to convert from world space to the Body’s local space.
-
inline float invMass() const
-
inline float invInertia() const
-
inline float mass() const
-
inline float inertia() const
-
inline bool isStructural() const
Whether the body is structural or not according to its dominance.
See also
-
bool interactsAsStructural() const
true if the body is structural in all of its constraints and has no velocity
This is mostly used internally.
See also
-
inline bool isAsleep() const
-
inline void wake()
-
inline auto constraints()
Returns an iterable view of Constraint*.
ie: for (Constraint* c : body.constraints())
-
inline auto constraints() const
Returns an iterable view of const Constraint*.
ie: for (const Constraint* c : body.constraints())
-
inline auto contacts()
-
inline auto contacts() const
Private Functions
-
inline virtual void setAllocator(const PhysicsAlloc &alloc) override
-
inline void update()
-
inline bool isImmobile(float velocityTreshold, float angularVelocityTreshold) const
-
inline void updateTimeImmobile(float dt, float velocityTreshold, float angularVelocityTreshold)
-
inline bool canSleep(float minTimeImmobile) const
-
inline void sleep()
Private Members
-
float dominance_
-
bool isAsleep_ = false
-
float timeImmobile_ = 0.f
-
std::vector<Constraint*, ReboundTo<Alloc, Constraint*>> constraints_
-
std::vector<ContactConstraint*, ReboundTo<Alloc, ContactConstraint*>> contacts_
Friends
- friend class Island
- friend class SolverProxy
- friend class World
- friend class Bodies
-
typedef PhysicsObject::PhysicsAlloc Alloc
-
struct BodyDescriptor
- #include <Body.hpp>
Describes a Body for construction.
Public Members
-
Vec2 position = {}
The initial position of the Body. This is a translation of the local-space geometry.
-
float orientation = {}
The initial orientation of the Body. This is a rotation around the body’s local space origin.
-
float dominance = 1.f
dominance scales the inverse mass of the Body when interacting in constraints.
A dominance of 0 means that the body has infinite mass and is considered structural. Ie when constrained with another body, only the other bodies will be acted upon.
A structural Body is not affected by any ForceField. Otherwise, ForceFields should not take dominance into account.
This parameter can be overriden for specific Constraints when passing Bodies.
See also
-
Vec2 position = {}
-
class BoundingBox
- #include <BoundingBox.hpp>
An axis-aligned bounding box defined by a minimum and maximum point.
If minimum == maximum, then the box is a single point.
The bounding box is invalid if any coordinates of minimum are greater than their maximum counterpart.
An invalid bounding box overlaps nothing and is ignored when combining boxes.
Public Functions
-
inline BoundingBox()
Creates an invalid bounding box.
-
template<VertexIterator2D It>
BoundingBox(It begin, It end) Creates a bounding box that contains all the vertices.
-
template<Geometry T>
BoundingBox(const T &geoemtry) Creates a bounding box that contains all the vertices of the geometry.
-
inline bool isValid() const
true if the bounding box covers a valid area,
See also
-
bool overlaps(const BoundingBox &other) const
true if this overlaps other, if the borders touch, the boxes overlap. If this or other is invalid, they never overlap.
-
bool contains(const BoundingBox &other) const
-
BoundingBox combined(const BoundingBox &other) const
Returns a bounding box that covers this and other.
-
inline bool operator==(const BoundingBox &other) const
true if both boxes are invalid or they have the same min and max coordinates.
-
inline bool operator!=(const BoundingBox &other) const
Public Static Functions
-
static BoundingBox scaled(BoundingBox original, float ratio)
-
inline BoundingBox()
-
class BoxSpawner : public simu::Tool
Public Functions
-
virtual void doGui() override
-
inline virtual const char *getName() const override
Public Members
-
float orientation = 0.f
-
float dominance = 1.f
-
float density = 1.f
-
float friction = 0.5f
-
float bounciness = 0.f
Public Static Attributes
-
static constexpr char name[] = "Box Spawner"
-
virtual void doGui() override
-
class Camera
-
class Collider
- #include <Collider.hpp>
Represents geometry that moves.
The Collider holds a local space Polygon and a set of transformed vertices that defines the geometry in world space.
All of its geometry is always positively oriented.
The local space geometry will be recentered to have its centroid at origin
Public Types
-
typedef FreeListAllocator<Vec2> Alloc
Public Functions
-
inline Collider(const ColliderDescriptor &descr, Body *body, const Alloc &alloc)
Creates a Collider from a local space polygon and an initial transform.
-
inline MassProperties properties() const
-
inline BoundingBox boundingBox() const
The world space bounding box of the Collider.
-
inline auto begin()
Iterators for the transformed geometry (world space vertices)
-
inline auto begin() const
-
inline auto end()
-
inline auto end() const
-
inline auto vertexView() const
Friends
- friend class World
-
typedef FreeListAllocator<Vec2> Alloc
-
struct ColliderDescriptor
-
class Colliders
-
Public Functions
-
Colliders() = default
-
inline auto begin() const
-
inline auto end() const
-
inline bool isEmpty() const
-
inline const MassProperties &properties() const
-
inline Collider *add(const ColliderDescriptor &descr, Body *owner)
Friends
- friend class Body
-
Colliders() = default
-
class ColliderTree : public simu::RTree<Collider*, FreeListAllocator<Collider*>>
Private Types
-
typedef RTree<Collider*, FreeListAllocator<Collider*>> Base
-
typedef RTree<Collider*, FreeListAllocator<Collider*>> Base
-
struct CombinableProperty
- #include <CombinableProperty.hpp>
A property that can be combined according to some Mode.
Some values are typically given for a system (collision restitution and friction coefficients), this class allows defining them per object and then combining them to obtain a value for the system.
Conception taken from https://docs.unity3d.com/Manual/class-PhysicMaterial.html
Public Types
Public Functions
-
inline CombinableProperty(CombinableProperty first, CombinableProperty second)
-
inline CombinableProperty(CombinableProperty first, CombinableProperty second)
-
template<class T, class U, simu::Uint32 m, simu::Uint32 n>
struct common_type<simu::Matrix<T, m, n>, simu::Matrix<U, m, n>>
-
class Constraint : public simu::PhysicsObject
- #include <ConstraintInterfaces.hpp>
Call sequence pseudo-code:
let S be the set of active constraints; foreach constraint c: if c.isActive(): S <- S U c; foreach constraint c in S: c.initSolve(); foreach constraint c in S: c.warmstart(); for i in range(world.nVelocityIterations) foreach constraint c in S: c.solveVelocities(); for i in range(world.nPositionIterations) foreach constraint c: c.solvePositions();
Subclassed by simu::ConstraintImplementation< TranslationMotorFunction >, simu::ConstraintImplementation< HingeConstraintFunction >, simu::ConstraintImplementation< DistanceConstraintFunction, LimitsSolver< DistanceConstraintFunction > >, simu::ConstraintImplementation< RotationConstraintFunction >, simu::ConstraintImplementation< MouseConstraintFunction >, simu::ConstraintImplementation< RotationMotorFunction >, simu::ConstraintImplementation< WeldConstraintFunction >, simu::ConstraintImplementation< F, S >, simu::ContactConstraint
Protected Functions
-
inline virtual bool shouldDie() const override
Offers an alternative death condition than this->kill().
Subclasses should always consider if Base::shouldDie() is true.
Example: a Constraint that is broken if the force it applies exceeds a treshold can implement this death condition in shouldDie.
-
inline virtual bool shouldDie() const override
-
template<ConstraintFunction... Fs>
class ConstraintFunctions -
Public Functions
-
template<ConstraintFunction F, ConstraintSolver S = EqualitySolver<F>>
class ConstraintImplementation : public simu::Constraint -
Public Functions
-
template<ConstraintFunction F_>
class ConstraintSolverBase Public Types
-
typedef Proxies::VelocityVec VelocityVec
Public Functions
-
inline void initBase()
Public Static Attributes
-
typedef Proxies::VelocityVec VelocityVec
-
class ContactConstraint : public simu::Constraint
Subclassed by simu::VisibleContactConstraint
Public Functions
-
inline ContactInfo contactInfo() const
-
inline virtual void preStep() override
Called at the start of World::step, after dead objects are removed.
Subclasses should always call Base::preStep().
This is called for Body, Constraint and then for ForceField.
Public Static Attributes
-
static constexpr float sinkTolerance = 3.f
Private Types
-
typedef std::array<JacobianRow, 2> JacobianRows
Private Functions
-
inline void updateContacts()
Private Members
-
ContactManifold manifold_
-
ContactManifold::FrameManifold frame_
-
union simu::ContactConstraint::[anonymous] [anonymous]
-
float restitutionCoeff_
-
float frictionCoeff_
-
inline ContactInfo contactInfo() const
-
struct ContactInfo
-
class ContactManifold
-
Public Functions
-
inline void update()
-
inline FrameManifold frameManifold(const Bodies &bodies) const
-
inline FrameManifold frameManifold(const Proxies &proxies) const
-
inline void setMinimumPenetration(float minPen)
-
inline float minimumPenetration() const
Private Functions
-
inline FrameManifold frameManifold(Transforms Ts) const
-
inline std::array<std::array<Vertex, 2>, 2> contacts(const Transforms &Ts) const
contacts()[referenceIndex()][1] -> second contact point of the reference body
-
inline Vec2 contactNormal(const Transforms &Ts) const
-
inline Vec2 contactTangent(const Transforms &Ts) const
Private Members
-
float minPen_
-
inline void update()
-
struct ContactStatus
-
struct DerefContact
Public Functions
-
inline ContactConstraint &operator()(typename ContactList::value_type &s) const
-
inline const ContactConstraint &operator()(const typename ContactList::value_type &s) const
-
inline ContactConstraint &operator()(typename ContactList::value_type &s) const
-
template<ConstraintFunction F, ConstraintFunction... Fs>
struct Dimension<F, Fs...> : public std::integral_constant<Uint32, F::dimension + Dimension<Fs...>::value>
-
class DistanceConstraint : public simu::ConstraintImplementation<DistanceConstraintFunction, LimitsSolver<DistanceConstraintFunction>>
Subclassed by simu::VisibleDistanceConstraint
Public Types
-
class DistanceConstraintFunction : public simu::EqualityConstraintFunctionBase<2, 1>
Public Types
-
typedef EqualityConstraintFunctionBase<2, 1> Base
Public Functions
-
typedef EqualityConstraintFunctionBase<2, 1> Base
-
struct Domain
-
struct DoubleDereference
- #include <View.hpp>
Dereferences the element one more time.
Propagates const, suppose a sequence of int*const * then a simple dereference returns int*const & and doubleDereference returns const int&
-
class Edge
Public Functions
-
inline Edge(It from, It to)
-
inline It fromIt() const
-
inline It toIt() const
-
inline float distanceSquaredToOrigin() const
Friends
- friend class Iterator
-
inline Edge(It from, It to)
-
template<Geometry T>
class Edges Public Functions
-
inline Iterator begin() const
-
inline Iterator end() const
-
inline Iterator next(Iterator edge) const
-
inline Iterator previous(Iterator edge) const
Private Types
-
typedef IteratorOf<const T> It
-
inline Iterator begin() const
-
template<Uint32 nBodies_, Uint32 dimension_>
class EqualityConstraintFunctionBase -
Public Functions
-
EqualityConstraintFunctionBase() = default
-
EqualityConstraintFunctionBase() = default
-
template<ConstraintFunction F>
class EqualitySolver : public simu::ConstraintSolverBase<F> Public Types
-
typedef ConstraintSolverBase<F> Base
Public Functions
Public Static Attributes
-
typedef ConstraintSolverBase<F> Base
-
struct Eval
-
class Event
Subclassed by simu::Keyboard, simu::Mouse
-
class Exception : public std::exception
Public Functions
-
inline char const *what() const noexcept override
-
inline char const *what() const noexcept override
-
class ForceField : public simu::PhysicsObject
Subclassed by simu::Gravity, simu::LinearField
Public Functions
-
~ForceField() override = default
Public Static Functions
-
~ForceField() override = default
-
struct FrameManifold
-
struct FreeBlock
Public Functions
-
template<class T, std::size_t blockSize = 32 * 1024>
class FreeListAllocator Public Types
-
typedef value_type *pointer
Public Functions
-
FreeListAllocator()
-
FreeListAllocator(const FreeListAllocator &other) noexcept
-
FreeListAllocator &operator=(const FreeListAllocator &other) noexcept
-
template<class U>
FreeListAllocator(const FreeListAllocator<U, blockSize> &other) noexcept
-
inline FreeListAllocator select_on_container_copy_construction() const noexcept
-
template<class U>
bool operator==(const FreeListAllocator<U, blockSize> &other) const noexcept
-
template<class U>
bool operator!=(const FreeListAllocator<U, blockSize> &other) const noexcept
-
template<class U>
FreeListAllocator(const FreeListAllocator<U, sz> &other) noexcept
-
template<class U>
bool operator==(const FreeListAllocator<U, sz> &other) const noexcept
-
template<class U>
bool operator!=(const FreeListAllocator<U, sz> &other) const noexcept
Friends
- friend class FreeListAllocator
-
typedef value_type *pointer
-
struct GeometricProperties
- #include <Geometry.hpp>
Compute properties of some non self-intersecting Geometry.
Convex, concave and geometry containing holes are all valid input. The hole(s) should be of opposite Orientation and attached to a vertex of the outer (solid) perimeter.
if area == 0, then the geometry isDegenerate (collinear) and the properties are undefined but no exception is raised
If vertices are negatively oriented, then the area is negative. Centroid and momentOfArea are unaffected.
Assuming constant density p, then mass = p * |area| inertia = p * momentOfArea
Public Functions
-
GeometricProperties() = default
-
GeometricProperties() = default
-
template<Geometry T = simu::Polygon>
class Gjk - #include <Gjk.hpp>
Determines if two collidable are in collision as well as the separation/penetration vector between them.
The boolean GJK algorithm is used upon construction and results are saved. If areColliding(), then calling penetration() uses the EPA algorithm (results are not saved)
If the the underlying Geometry of the Collidables is concave or has holes, only their convex hulls are considered.
Warning
changing first or second between construction and calls to any method is undefined.
Public Functions
-
inline bool areColliding() const
-
Vec2 separation()
Minimum translation vector such that areColliding() would be true.
It is the vector of the closest feature of first to the closest feature of second
If areColliding(), returns a null vector.
In order to make first and second only touch, both are equivalent:
translate first by separation()
translate seccond by -separation()
-
Vec2 penetration() const
Minimum translation vector such that first and second are only touching.
It is the vector of the penetration of second into first
If not areColliding(), returns a null vector.
In order to make first and second only touch, both are equivalent:
translate first by -penetration()
translate second by penetration()
-
inline bool areColliding() const
-
class Grabber : public simu::Tool
Public Functions
-
inline virtual void doGui() override
-
inline virtual const char *getName() const override
Public Static Attributes
-
static constexpr char name[] = "Grabber"
Private Functions
-
VisibleMouseConstraint *makeMouseConstraint(Body *b, Vec2 pos)
-
inline virtual void doGui() override
-
class Gravity : public simu::ForceField
Public Functions
-
class HingeConstraint : public simu::ConstraintImplementation<HingeConstraintFunction>
Public Types
-
typedef ConstraintImplementation<HingeConstraintFunction> Base
-
typedef HingeConstraintFunction F
-
typedef ConstraintImplementation<HingeConstraintFunction> Base
-
class HingeConstraintFunction : public simu::EqualityConstraintFunctionBase<2, 2>
Public Types
-
typedef EqualityConstraintFunctionBase<2, 2> Base
Public Functions
Private Members
-
typedef EqualityConstraintFunctionBase<2, 2> Base
-
template<Uint32 nBodies_, Uint32 dimension_>
class InequalityConstraintFunctionBase -
Public Functions
-
InequalityConstraintFunctionBase() = default
-
InequalityConstraintFunctionBase() = default
-
template<ConstraintFunction F>
class InequalitySolver : public simu::ConstraintSolverBase<F> Public Types
-
typedef ConstraintSolverBase<F> Base
Public Functions
Public Static Attributes
-
typedef ConstraintSolverBase<F> Base
-
struct Input
-
struct Input
-
template<class T>
class Interval - #include <Interval.hpp>
Interval or range of values.
The min and max of the interval are always included. if min > max, then the interval is degenerate and contains nothing. if min == max, the interval contains a single value.
-
struct InvMasses
-
template<class F>
struct IsCallableStrictReturn : public std::integral_constant<bool, std::is_same_v<std::invoke_result_t<F, A...>, R> && std::is_invocable_r_v<R, F, A...>>
-
class Island
Public Types
-
typedef PhysicsObject::PhysicsAlloc Alloc
Public Functions
-
inline void clear()
-
inline bool hasConstraints()
-
inline bool isAwake() const
-
inline auto bodies()
-
inline auto constraints()
-
inline auto contacts()
-
inline void refreshProxies()
-
inline void integrateBodies(float dt)
-
inline void endSolve()
Private Functions
Private Members
-
std::vector<Constraint*, ReboundTo<Alloc, Constraint*>> constraints_
-
std::vector<ContactConstraint*, ReboundTo<Alloc, ContactConstraint*>> contacts_
-
bool isAwake_ = false
-
typedef PhysicsObject::PhysicsAlloc Alloc
-
template<std::forward_iterator Iter, std::invocable<decltype(*std::declval<Iter>())> Deref>
class Iterator -
Public Functions
-
Iterator() = default
-
Iterator() = default
-
class Iterator
Public Types
Public Functions
-
template<bool isConst>
class Iterator Public Types
Public Functions
- template<bool otherIsConst> inline requires (isConst||!otherIsConst) Iterator(const Iterator< otherIsConst > &other)
-
inline BoundingBox bounds() const
-
template<bool otherIsConst>
inline bool operator==(const Iterator<otherIsConst> &other) const
-
template<bool otherIsConst>
inline bool operator!=(const Iterator<otherIsConst> &other) const
Private Functions
-
inline void goLeft()
-
struct JacobianBuilder
-
class Keyboard : public simu::Event
Public Types
-
enum Modifier
Values:
-
enumerator shift
-
enumerator control
-
enumerator alt
-
enumerator super
-
enumerator capsLock
-
enumerator numLock
-
enumerator shift
-
enum class Key
Values:
-
enumerator unknown
-
enumerator space
-
enumerator apostrophe
-
enumerator comma
-
enumerator minus
-
enumerator period
-
enumerator slash
-
enumerator key0
-
enumerator key1
-
enumerator key2
-
enumerator key3
-
enumerator key4
-
enumerator key5
-
enumerator key6
-
enumerator key7
-
enumerator key8
-
enumerator key9
-
enumerator semicolon
-
enumerator equal
-
enumerator A
-
enumerator B
-
enumerator C
-
enumerator D
-
enumerator E
-
enumerator F
-
enumerator G
-
enumerator H
-
enumerator I
-
enumerator J
-
enumerator K
-
enumerator L
-
enumerator M
-
enumerator N
-
enumerator O
-
enumerator P
-
enumerator Q
-
enumerator R
-
enumerator S
-
enumerator T
-
enumerator U
-
enumerator V
-
enumerator W
-
enumerator X
-
enumerator Y
-
enumerator Z
-
enumerator leftBracket
-
enumerator backslash
-
enumerator rightBracket
-
enumerator graveAccent
-
enumerator world1
-
enumerator world2
-
enumerator escape
-
enumerator enter
-
enumerator tab
-
enumerator backspace
-
enumerator insert
-
enumerator del
-
enumerator right
-
enumerator left
-
enumerator down
-
enumerator up
-
enumerator pageUp
-
enumerator pageDown
-
enumerator home
-
enumerator end
-
enumerator capsLock
-
enumerator scrollLock
-
enumerator numLock
-
enumerator printScreen
-
enumerator pause
-
enumerator F1
-
enumerator F2
-
enumerator F3
-
enumerator F4
-
enumerator F5
-
enumerator F6
-
enumerator F7
-
enumerator F8
-
enumerator F9
-
enumerator F10
-
enumerator F11
-
enumerator F12
-
enumerator F13
-
enumerator F14
-
enumerator F15
-
enumerator F16
-
enumerator F17
-
enumerator F18
-
enumerator F19
-
enumerator F20
-
enumerator F21
-
enumerator F22
-
enumerator F23
-
enumerator F24
-
enumerator F25
-
enumerator keypad0
-
enumerator keypad1
-
enumerator keypad2
-
enumerator keypad3
-
enumerator keypad4
-
enumerator keypad5
-
enumerator keypad6
-
enumerator keypad7
-
enumerator keypad8
-
enumerator keypad9
-
enumerator keypadDecimal
-
enumerator keypadDivide
-
enumerator keypadMultiply
-
enumerator keypadSubstract
-
enumerator keypadAdd
-
enumerator keypadEnter
-
enumerator keypadEqual
-
enumerator leftShift
-
enumerator leftControl
-
enumerator leftAlt
-
enumerator leftSuper
-
enumerator rightShift
-
enumerator rightControl
-
enumerator rightAlt
-
enumerator rightSuper
-
enumerator unknown
-
enum Modifier
-
struct LambdaClamper
-
template<ConstraintFunction F>
class LimitsSolver : public simu::ConstraintSolverBase<F> - #include <ConstraintSolver.hpp>
Adds upper and lower limits to a constraint.
Given a constraint of the form C(s): f(s) - a = 0 where f(s) is a function depending on the state of the bodies and a is a constant,
defines the constraints: lower limit: CL(s): C(s) - L >= 0 (f(s) >= a + L) upper limit: CU(s): -C(s) + U >= 0 (f(s) <= a + H) with L and U constant offsets from a, L <= U.
If L == U, then the equality constraint CE(s): f(s) - a - L = 0 is applied
This is not typically used with constraints of more than one dimension.
Public Types
-
typedef ConstraintSolverBase<F> Base
Public Functions
Public Static Attributes
Private Types
Private Functions
-
inline void assertLimits() const
-
typedef ConstraintSolverBase<F> Base
-
class LinearField : public simu::ForceField
Public Functions
-
inline explicit LinearField(Vec2 force, const Domain &domain = ForceField::global())
-
inline explicit LinearField(Vec2 force, const Domain &domain = ForceField::global())
-
struct LineBarycentric
- #include <BarycentricCoordinates.hpp>
Barycentric coordinates of Q for the line A -> B.
closestPoint is the point on A->B closest to Q
The following equation holds if u and v are both greater than 0: closestPoint = u*A + v*B;
coordinates are normalized, they are such that u+v = 1
-
struct MassProperties
Public Functions
-
MassProperties() = default
Friends
-
inline friend MassProperties operator+(const MassProperties &lhs, const MassProperties &rhs)
-
MassProperties() = default
-
struct Material
- #include <Material.hpp>
Defines the material of a Collider.
Public Members
-
float density = 1.f
The weight per unit of area, must be greater than 0.
-
CombinableProperty bounciness = {0.f, CombinableProperty::average}
How much the body will bounce when colliding with another.
The value should be in [0, 1]. A value of 0 means the object does not bounce at all (all energy is lost) A value of 1 means the object fully bounces (no energy is lost)
behavior is undefined if e <= -1
This value is combined to obtain a coefficient of restitution: https://en.wikipedia.org/wiki/Coefficient_of_restitution
-
CombinableProperty friction = {0.f, CombinableProperty::average}
How much the body resists to sliding against another.
The value will typically be in [0, 1]. A value of 0 implies a very slippery object (ice)
This value is combined to obtain a coefficient of friction: https://simple.wikipedia.org/wiki/Coefficient_of_friction
-
CombinableProperty penetration = {0.005f, CombinableProperty::average}
How much penetration the body tolerates during collisions.
This value should be small enough that there is no visible overlapping, while being big enough relative to a Body’s geometry to compute correct ContactManifolds.
It is also used to determine if a ContactManifold is still valid. if the contact points between two bodies are closer than penetration, the contact is considered valid.
This means that the Body
’s geometry’s vertices should have a distance of more
than twice the
Material’s penetration between them.
-
float density = 1.f
-
template<class T, Uint32 m, Uint32 n>
struct Matrix : public simu::MatrixData<T, m, n>, public simu::SpecialConstructors<T, m, n> - #include <Matrix.hpp>
Matrix class for small matrices.
Most operations are provided as global functions
See also
Public Static Functions
-
template<class T, Uint32 mRows_, Uint32 nCols_>
struct MatrixData - #include <Matrix.hpp>
Matrix data, stored row-major.
Two methods for random access are provided, For matrices, mat(i, j) is recommended For vectors, vec[i] is recommended
Direct access to the data member is allowed, but for matrices it is preferable to use operator() to avoid errors
Subclassed by simu::Matrix< float, dimension >, simu::Matrix< float, 3, 3 >, simu::Matrix< Uint8, 4 >, simu::Matrix< float, 2 >, simu::Matrix< float, 2, 6 >
Public Functions
-
MatrixData() = default
-
template<class U>
inline explicit MatrixData(const MatrixData<U, mRows_, nCols_> &other)
-
inline const_iterator begin() const
-
inline const_iterator end() const
-
template<class U>
MatrixData(const MatrixData<U, m, n> &other)
-
MatrixData() = default
-
template<class MatrixT>
class MatrixRowManipulator Public Functions
-
inline MatrixRowManipulator()
-
template<class SubMatrixT>
inline void assign(Uint32 begin, const SubMatrixT &subMat)
Private Types
-
typedef MatrixRows::value_type Row
-
inline MatrixRowManipulator()
-
template<Uint32 dimension_>
class MotorFunctionBase -
Public Functions
-
inline MotorFunctionBase(float maxVelocity, float maxForce)
-
inline float throttle() const
-
inline void throttle(float throttle)
Public Static Attributes
-
static constexpr Uint32 dimension = dimension_
-
inline MotorFunctionBase(float maxVelocity, float maxForce)
-
class MouseConstraint : public simu::ConstraintImplementation<MouseConstraintFunction>
Subclassed by simu::VisibleMouseConstraint
Public Functions
Private Types
-
typedef ConstraintImplementation<MouseConstraintFunction> Base
-
typedef ConstraintImplementation<MouseConstraintFunction> Base
-
class MouseConstraintFunction : public simu::EqualityConstraintFunctionBase<1, 2>
Public Types
-
typedef EqualityConstraintFunctionBase<1, 2> Base
Public Functions
-
typedef EqualityConstraintFunctionBase<1, 2> Base
-
struct Node
-
class NoTool : public simu::Tool
Public Functions
-
NoTool() = default
-
inline virtual void doGui() override
-
inline virtual const char *getName() const override
Public Static Attributes
-
static constexpr char name[] = "No Tool"
-
NoTool() = default
-
template<ConstraintFunction F>
struct NProxies<F> : public std::integral_constant<Uint32, F::nBodies>
-
template<ConstraintFunction F1, ConstraintFunction F2, ConstraintFunction... Fs>
struct NProxies<F1, F2, Fs...> : public simu::details::NProxies<F1>
-
class OverlapList
-
Public Functions
-
inline OverlapList(const OverlapList &other)
-
OverlapList(OverlapList &&other) = default
-
inline void sortOverlapping(const BoundingBox &box)
-
inline auto overlapping()
-
inline auto overlapping() const
-
inline OverlapList(const OverlapList &other)
-
template<class ...Args>
struct Pack
-
class PhysicsObject
- #include <PhysicsObject.hpp>
Base class of physics objects.
The lifetime of physics objects is managed by World. Instead of explicitly removing them from the world, objects must specify themselves when they should be removed.
Objects will be removed if they are killed with PhysicsObject::kill() or when some condition is satisfied in the virtual PhysicsObject::shouldDie() method.
The actual removal will be done at the beginning of World::step(). Since some objects may want to remove themselves once some other object dies, no object is truly removed until PhysicsObject::isDead() is called on all objects of the world. This means that objects can query other objects in their shouldDie() method without worrying about accessing released memory. The shouldDie() method can also be used to update references to dying objects (which is why it is not const).
Some objects may want to spawn objects when they are created and kill them when they are destroyed, this can be done with PhysicsObject::onConstruction(world) and PhysicsObject::onDestruction(world). Again, onDestruction will be called for all objects that will be destroyed before any object is truly removed and their memory released.
Subclassed by simu::Body, simu::Constraint, simu::ForceField
Public Types
-
typedef FreeListAllocator<PhysicsObject> PhysicsAlloc
Public Functions
-
virtual ~PhysicsObject() = default
-
inline bool isDead() const
-
inline void kill()
Protected Functions
-
inline virtual void setAllocator(const PhysicsAlloc&)
-
inline virtual void onConstruction(World&)
Called when a World creates this object.
Subclasses should always call Base::onConstruction
-
inline virtual void onDestruction(World&)
Called when a World destroys this object.
Subclasses should always call Base::onDestruction
See also
-
inline virtual void onKill()
Called when this object is requested to die (by a call to kill())
Subclasses should always call Base::onKill
This is different from onDestruction since this object is not destroyed immediately after this call. It will be destroyed the next time World::step is called on the World owning this object.
This method should be used to kill other objects linked to this one. For example a composed Body may create other objects with onConstruction, keep a reference to them and kill them when it is killed with onKill.
-
inline virtual bool shouldDie() const
Offers an alternative death condition than this->kill().
Subclasses should always consider if Base::shouldDie() is true.
Example: a Constraint that is broken if the force it applies exceeds a treshold can implement this death condition in shouldDie.
-
inline virtual void preStep()
Called at the start of World::step, after dead objects are removed.
Subclasses should always call Base::preStep().
This is called for Body, Constraint and then for ForceField.
-
inline virtual void postStep()
Called at the end of World::step.
Subclasses should always call Base::postStep().
This is called for Body, Constraint and then for ForceField.
Protected Attributes
- friend World
Private Members
-
bool killed_ = false
-
typedef FreeListAllocator<PhysicsObject> PhysicsAlloc
-
class Polygon
- #include <Polygon.hpp>
A polygon has at least 3 vertices in a positive Orientation.
Polygons are allowed to be concave and have holes as long as they do not self-intersect, in which case behavior is undefined.
The vertices are reordered to be positively oriented. The GeometricProperties are modified to reflect this change.
Polygons are not allowed to modify their vertices after construction.
Warning
no special measures are taken if properties indicate that the geometry isDegenerate.
-
struct Polytope
-
Public Functions
-
struct PosLambdaClamper
-
struct Profiler
-
class Proxies
Public Types
Public Functions
-
Proxies() = default
-
inline Proxies(const SolverProxy &p0, const SolverProxy &p1, const InvMasses &masses)
-
inline SolverProxy const *begin() const
-
inline SolverProxy const *end() const
-
inline SolverProxy *begin()
-
inline SolverProxy *end()
-
inline SolverProxy &operator[](Uint32 index)
-
inline const SolverProxy &operator[](Uint32 index) const
-
inline VelocityVec velocity() const
-
Proxies() = default
-
class Random
Public Static Functions
-
template<class U>
struct rebind
-
class Renderer
Subclassed by simu::OpenGlRenderer
Public Types
Public Functions
-
inline Renderer()
-
virtual ~Renderer() = default
-
virtual void flush() = 0
-
void drawContouredPolygon(Vec2 center, Poly vertices, Rgba fillColor, Rgba contourColor, float contourWidth, Contour contour = Contour::outside)
-
inline float getLineWidth() const
-
inline void setLineWidth(float width)
-
inline float getPointRadius() const
-
inline void setPointRadius(float radius)
Protected Types
-
typedef FreeListAllocator<Vec2> Alloc
-
inline Renderer()
-
class Rotation
Public Functions
-
inline explicit Rotation(float theta)
-
inline float theta() const
-
inline void set(float theta)
Private Functions
-
inline Rotation(float theta, float c, float s)
-
inline explicit Rotation(float theta)
-
class RotationConstraint : public simu::ConstraintImplementation<RotationConstraintFunction>
Public Types
-
typedef ConstraintImplementation<RotationConstraintFunction> Base
-
typedef RotationConstraintFunction F
-
typedef ConstraintImplementation<RotationConstraintFunction> Base
-
class RotationConstraintFunction : public simu::EqualityConstraintFunctionBase<2, 1>
Public Types
-
typedef EqualityConstraintFunctionBase<2, 1> Base
Public Functions
Private Members
-
Value initialAngle_
-
typedef EqualityConstraintFunctionBase<2, 1> Base
-
class RotationMotor : public simu::ConstraintImplementation<RotationMotorFunction>
-
class RotationMotorFunction : public simu::MotorFunctionBase<1>
Public Types
-
typedef MotorFunctionBase<1> Base
-
typedef MotorFunctionBase<1> Base
-
template<class T, class Allocator = std::allocator<T>>
class RTree -
Public Functions
-
inline ~RTree()
-
template<Callable<void(iterator)> F>
inline void forEachIn(BoundingBox box, const F &func)
-
template<Callable<void(iterator, iterator)> F>
inline void forEachOverlapping(const ViewType<iterator*> &iterators, const F &func)
-
template<Callable<BoundingBox(iterator)> Update, Callable<void(iterator, iterator)> OnCollision>
inline void updateAndCollide(const Update &update, const OnCollision &onCollision)
-
inline const_iterator begin() const
-
inline const_iterator end() const
-
inline iterator insert(BoundingBox bounds, const_reference val)
-
template<class ...Args>
inline iterator emplace(BoundingBox bounds, Args&&... args)
-
inline iterator update(iterator it, BoundingBox newBounds)
-
inline void clear()
-
inline bool isEmpty() const
-
inline BoundingBox bounds() const
-
inline BoundingBox bounds(const_iterator it) const
Private Types
-
typedef AllocTraits::template rebind_alloc<Node> NodeAllocator
-
typedef AllocTraits::template rebind_traits<Node> NodeAllocTraits
Private Functions
-
inline Node *makeNode(const BoundingBox &bounds = BoundingBox{})
-
template<class ...Args>
inline Node *makeLeaf(const BoundingBox &bounds, Args&&... args)
-
inline void deleteNode(Node *node)
-
inline void swapNodes(Node *first, Node *second)
-
inline void checkRotations(Node *grandParent)
-
inline void checkRotation(Node *upper, Node *lower)
-
inline void refit(Node *node)
-
inline void addLeafTo(Node *node, Node *leaf)
-
inline float area(BoundingBox bounds)
-
inline BoundingBox bounds(Node *node)
-
inline Node *extract(Node *node)
-
inline void erase(Node *node)
-
template<class F>
inline void forEachIn(const BoundingBox &box, const F &func, Node *node)
-
template<class OnCollision>
inline Node *updateAndCollide(ViewType<Node**> nodes, OverlapList collisions, const OnCollision &onCollision, RecycleBin &bin)
-
inline void update(Node *node, BoundingBox newBounds)
-
inline ~RTree()
-
class Scene
Public Functions
-
inline Scene()
-
virtual ~Scene() = default
-
inline bool isInit() const
-
inline void reset()
-
inline void setPlaySpeed(float speed)
-
inline float playSpeed() const
-
inline void resume()
-
inline void pause()
-
inline bool isPaused() const
-
inline void step(float dt)
-
inline Application *app()
-
inline const Application *app() const
Protected Functions
-
inline virtual void doGui()
-
inline virtual void onClear()
-
inline virtual void preStep(float)
-
inline virtual void postStep(float)
-
virtual void moveCamera(float dt)
-
inline void registerAllTools()
Private Functions
-
void init(Application *app)
-
inline Scene()
-
class ScopedTimer
-
struct Settings
-
template<class Signature>
struct SignatureDecomposition
-
struct Simplex
Public Functions
-
inline bool containsOrigin() const
Public Members
Private Members
-
mutable bool keepBottomPoint_ = false
-
inline bool containsOrigin() const
-
template<class T>
class Solver<T, 2> Public Functions
-
inline bool isValid() const
Friends
- friend class LcpSolver
-
inline bool isValid() const
-
class SolverProxy
Public Functions
-
SolverProxy() = default
-
inline float orientation() const
-
inline float angularVelocity() const
Friends
- friend class Bodies
- friend class Proxies
-
SolverProxy() = default
-
template<class T, Uint32 m, Uint32 n, bool isSquare = (m == n)>
struct SpecialConstructors Subclassed by simu::Matrix< float, dimension >, simu::Matrix< T, n, n >, simu::Matrix< T, 2, 2 >, simu::Matrix< float, 3, 3 >, simu::Matrix< Uint8, 4 >, simu::Matrix< float, 2 >, simu::Matrix< float, 2, 6 >, simu::Matrix< T, m, n >
-
class Specs
-
Public Static Functions
-
class TimeEntry
Public Types
Public Functions
-
TimeEntry() = default
-
inline double last() const
-
inline double average() const
-
inline double max() const
-
inline ScopedTimer time()
-
inline void startPartial()
-
inline ScopedTimer timePartial()
-
inline void commitPartial()
-
TimeEntry() = default
-
class Tool
Subclassed by simu::BoxSpawner, simu::Grabber, simu::NoTool
-
class Transform
Public Functions
-
inline explicit Transform()
-
inline Transform(Rotation r, Translation t)
-
inline const Translation &translation() const
The translation part of this transform.
-
inline Translation &translation()
Public Static Functions
-
static inline Rotation rotation(float theta)
Rotates a 2D vector by theta radians around the origin {0, 0}.
-
static inline Translation translation(Vec2 offset)
Translate a 2D vector by offset.
-
inline explicit Transform()
-
class Translation
Public Functions
-
inline Translation inverse() const
-
inline Translation operator*=(const Translation &other)
-
inline Translation operator*(const Translation &other) const
-
inline Translation inverse() const
-
class TranslationMotor : public simu::ConstraintImplementation<TranslationMotorFunction>
-
class TranslationMotorFunction : public simu::MotorFunctionBase<2>
Public Types
-
typedef MotorFunctionBase<2> Base
-
typedef MotorFunctionBase<2> Base
-
struct TriangleBarycentric
- #include <BarycentricCoordinates.hpp>
Barycentric coordinates of Q for the triangle ABC.
ABC can be given in any winding order.
closestPoint will be on vertices or edges if Q is outside ABC, else closestPoint = Q.
Warning
coordinates are not normalized, they are such that u+v+w = abs(area(ABC))
-
class Velocity
-
struct Vertex
-
class Visible
Subclassed by simu::VisibleBody, simu::VisibleContactConstraint, simu::VisibleDistanceConstraint, simu::VisibleMouseConstraint
-
class VisibleBody : public simu::Body, public simu::Visible
Public Functions
-
inline VisibleBody(BodyDescriptor descr, Rgba color, Renderer *renderer)
Protected Functions
-
inline virtual void postStep() override
Called at the end of World::step.
Subclasses should always call Base::postStep().
This is called for Body, Constraint and then for ForceField.
-
inline VisibleBody(BodyDescriptor descr, Rgba color, Renderer *renderer)
-
class VisibleContactConstraint : public simu::ContactConstraint, public simu::Visible
Public Functions
Protected Functions
-
inline virtual void postStep() override
Called at the end of World::step.
Subclasses should always call Base::postStep().
This is called for Body, Constraint and then for ForceField.
-
inline virtual void postStep() override
-
class VisibleDistanceConstraint : public simu::DistanceConstraint, public simu::Visible
Public Functions
-
inline VisibleDistanceConstraint(const Bodies &bodies, std::array<Vec2, 2> fixedPoints, Renderer *renderer, bool disableContacts = true)
Protected Functions
-
inline virtual void postStep() override
Called at the end of World::step.
Subclasses should always call Base::postStep().
This is called for Body, Constraint and then for ForceField.
-
inline VisibleDistanceConstraint(const Bodies &bodies, std::array<Vec2, 2> fixedPoints, Renderer *renderer, bool disableContacts = true)
-
class VisibleMouseConstraint : public simu::MouseConstraint, public simu::Visible
-
Protected Functions
-
inline virtual void postStep() override
Called at the end of World::step.
Subclasses should always call Base::postStep().
This is called for Body, Constraint and then for ForceField.
-
inline virtual void postStep() override
-
class WeldConstraint : public simu::ConstraintImplementation<WeldConstraintFunction>
Public Types
-
typedef HingeConstraintFunction HingeF
-
typedef RotationConstraintFunction RotF
-
typedef WeldConstraintFunction F
-
typedef ConstraintImplementation<F> Base
-
typedef HingeConstraintFunction HingeF
-
class World
- #include <World.hpp>
The World class makes the ForceField, Body and Constraint classes interact.
Collisions are detected discretely, and the corresponding constraints are managed by the world.
The World owns all objects that are put into it. For object lifetime management, see PhysicsObject.
Public Types
-
typedef PhysicsObject::PhysicsAlloc Alloc
-
typedef ReboundTo<Alloc, UniquePtr<ContactConstraint>> ContactAlloc
- std::function< UniquePtr< ContactConstraint >Collider &, Collider &, const ContactAlloc &)> ContactFactory
Public Functions
-
World(ContactFactory makeContact = defaultContactFactory)
Construct an empty world.
-
inline void clear()
-
inline void setContactFactory(ContactFactory makeContact)
-
inline auto bodies()
Gives a view over the Bodies in the world.
ie for ( [const] Body& body : world.bodies())
-
inline auto bodies() const
-
inline auto forceFields()
Gives a view over the ForceFields in the world.
ie for ( [const] ForceField& force : world.forceFields())
-
inline auto forceFields() const
-
inline auto constraints()
Gives a view over the Constraints in the world.
ie for ( [const] Constraint& constraint : world.constraints())
-
inline auto constraints() const
-
inline auto contacts()
Gives a view over the ContactConstraints in the world.
ie for ( [const] ContactConstraint& contact : world.contacts())
-
inline auto contacts() const
-
template<std::derived_from<Body> T, class ...Args>
inline T *makeBody(Args&&... args) Construct a Body and puts it in the world.
-
inline Body *makeBody(const BodyDescriptor &descr)
-
template<std::derived_from<Constraint> T, class ...Args>
inline T *makeConstraint(Args&&... args) Construct a Constraint and puts it in the world.
-
template<std::derived_from<ForceField> T, class ...Args>
inline T *makeForceField(Args&&... args) Construct a ForceField and puts it in the world.
-
void step(float dt)
Makes the world progress in time.
ForceFields are applied to non-structural bodies, contacts are updated, killed objects are removed, constraints are enforce and bodies are moved.
-
template<Callable<void(Body*)> F>
inline void forEachIn(BoundingBox box, const F &func)
Public Static Attributes
-
static ContactFactory defaultContactFactory
Private Types
-
typedef ReboundTo<Alloc, UniquePtr<Constraint>> ConstraintAlloc
-
typedef ReboundTo<Alloc, UniquePtr<ForceField>> ForceFieldAlloc
-
typedef std::list<UniquePtr<Constraint>, ConstraintAlloc> ConstraintList
-
typedef std::list<UniquePtr<ForceField>, ForceFieldAlloc> ForceFieldList
Private Functions
-
UniquePtr<ContactConstraint> makeContactConstraint(Collider &first, Collider &second)
-
template<std::derived_from<PhysicsObject> T, class A, class ...Args>
inline UniquePtr<T> makeObject(A &alloc, Args&&... args)
-
void applyForces(float dt)
-
void cleanup()
-
void updateBodies(float dt)
-
inline ContactList::iterator inContacts(const std::array<simu::Collider*, 2> &colliders)
Private Members
- friend Body
-
BodyAlloc bAlloc_ = {miscAlloc_}
-
ConstraintAlloc cAlloc_ = {bAlloc_}
-
ForceFieldAlloc fAlloc_ = {miscAlloc_}
-
ConstraintList constraints_ = {cAlloc_}
-
ForceFieldList forces_ = {fAlloc_}
-
ContactList contacts_ = {miscAlloc_}
-
ColliderTree colliderTree_ = {bAlloc_}
-
ContactFactory makeContactConstraint_
-
typedef PhysicsObject::PhysicsAlloc Alloc
-
namespace details
-
namespace simu
Typedefs
-
template<class T>
using IteratorOf = decltype(std::declval<T>().begin()) The iterator type returned by T::begin()
-
template<class T, Uint32 dim>
using Vector = Matrix<T, dim, 1> Vector class.
Vectors are always column vectors, use transpose(vec) to obtain a row vector when needed.
-
template<Uint32 m, Uint32 n>
using ComparisonMatrix = MatrixData<bool, m, n> Comparison Matrix returned by comparisons of matrices.
This is not convertible to bool, use the functions all() and any() to evaluate to a bool.
All matrix comparisons are done element-wise.
element-wise boolean operators are also provided for ComparisonMatrix
-
typedef ConstraintFunctions<HingeConstraintFunction, RotationConstraintFunction> WeldConstraintFunction
-
typedef TimeEntry::ScopedTimer ScopedTimer
Enums
Functions
-
Orientation orientation(Vertex v0, Vertex v1, Vertex v2, float epsilon = simu::EPSILON)
Find the Orientation of 3 vertices.
epsilon is used to approximate collinearity
-
template<class T, class U, Uint32 m, Uint32 n>
inline Matrix<Promoted<T, U>, m, n> operator+(const Matrix<T, m, n> &lhs, const Matrix<U, m, n> &rhs)
-
template<class T, class U, Uint32 m, Uint32 n>
inline Matrix<Promoted<T, U>, m, n> operator-(const Matrix<T, m, n> &lhs, const Matrix<U, m, n> &rhs)
-
template<class T, class U, Uint32 m, Uint32 n>
inline Matrix<Promoted<T, U>, m, n> operator*(U scalar, const Matrix<T, m, n> &mat)
-
template<class T, class U, Uint32 m, Uint32 n>
inline Matrix<Promoted<T, U>, m, n> operator*(const Matrix<T, m, n> &mat, U scalar)
-
template<class T, class U, Uint32 m, Uint32 n>
inline Matrix<Promoted<T, U>, m, n> operator/(const Matrix<T, m, n> &mat, U scalar)
-
template<class T, class U, Uint32 mLeft, Uint32 nLeft, Uint32 nRight>
inline Matrix<Promoted<T, U>, mLeft, nRight> operator*(const Matrix<T, mLeft, nLeft> &lhs, const Matrix<U, nLeft, nRight> &rhs)
-
template<class T, Uint32 m, Uint32 n>
inline Matrix<T, n, m> transpose(const Matrix<T, m, n> &original)
-
template<class T, class U, Uint32 n>
inline Vector<Promoted<T, U>, n> solve(const Matrix<T, n, n> &A, const Vector<U, n> &b) Return x such that Ax = b.
-
template<class T, Uint32 n, std::invocable<Vector<T, n>, Uint32> Proj>
inline Vector<T, n> solveInequalities(const Matrix<T, n, n> &A, Vector<T, n> b, Proj proj, Vector<T, n> initialGuess = Vector<T, n>{}, float epsilon = simu::EPSILON) Return x such that Ax >= b with bounds on x.
proj must project x onto its valid bounds (ie clamp its values). With the following signature: T proj(const Vector<T, n>& x, Uint32 index) where x[index] must be clamped and returned.
when the absolute change of components of x drops below epsilon, iteration terminates.
Uses projected Gauss-Seidel to solve the MLCP, See A. Enzenhofer’s master thesis (McGill): Numerical Solutions of MLCP
proj must project x onto its valid bounds (ie clamp its values).
when the absolute change of components of x drops below epsilon, iteration terminates.
Uses projected Gauss-Seidel to solve the MLCP, See A. Enzenhofer’s master thesis (McGill): Numerical Solutions of MLCP
-
template<class T>
inline Vector<T, 2> solveLcp(const Matrix<T, 2, 2> &A, const Vector<T, 2> &b) Solves the LCP Ax >= b with x >= 0.
This gives Ax - b = w with the residuals w >= 0, the complementarity condition is dot(x, w) = 0 (xi = 0 or wi = 0 for each index i)
Uses total enumeration, taken from box2d’s contact solver. If no value is returned, the LCP had no solution.
-
template<class T, class U, Uint32 dim>
inline Vector<Promoted<T, U>, dim> elementWiseMul(const Vector<T, dim> &lhs, const Vector<U, dim> &rhs)
-
template<class T, class U, Uint32 dim>
inline Promoted<T, U> dot(const Vector<T, dim> &lhs, const Vector<U, dim> &rhs)
-
template<class T, class U>
inline Vector<Promoted<T, U>, 3> cross(const Vector<T, 3> &lhs, const Vector<U, 3> &rhs)
-
template<class T, class U>
inline Promoted<T, U> cross(const Vector<T, 2> &lhs, const Vector<U, 2> &rhs)
-
template<class T, class U, Uint32 dim>
inline Vector<Promoted<T, U>, dim> projection(const Vector<T, dim> &ofThis, const Vector<U, dim> &onThat)
-
template<class T>
inline Vector<T, 2> perp(const Vector<T, 2> &v, bool clockwise = false) rotates v by 90 degrees
If clockwise is false, then this is (k x v) If clockwise is true, then this is (v x k)
-
template<class T, class U, Uint32 m, Uint32 n>
inline ComparisonMatrix<m, n> operator==(const Matrix<T, m, n> &lhs, const Matrix<U, m, n> &rhs)
-
template<class T, class U, Uint32 m, Uint32 n>
inline ComparisonMatrix<m, n> operator!=(const Matrix<T, m, n> &lhs, const Matrix<U, m, n> &rhs)
-
template<class T, class U, Uint32 m, Uint32 n>
inline ComparisonMatrix<m, n> operator<(const Matrix<T, m, n> &lhs, const Matrix<U, m, n> &rhs)
-
template<class T, class U, Uint32 m, Uint32 n>
inline ComparisonMatrix<m, n> operator<=(const Matrix<T, m, n> &lhs, const Matrix<U, m, n> &rhs)
-
template<class T, class U, Uint32 m, Uint32 n>
inline ComparisonMatrix<m, n> operator>(const Matrix<T, m, n> &lhs, const Matrix<U, m, n> &rhs)
-
template<class T, class U, Uint32 m, Uint32 n>
inline ComparisonMatrix<m, n> operator>=(const Matrix<T, m, n> &lhs, const Matrix<U, m, n> &rhs)
-
template<Uint32 m, Uint32 n>
inline bool all(const ComparisonMatrix<m, n> &comp) true if all elements are true
-
template<Uint32 m, Uint32 n>
inline bool any(const ComparisonMatrix<m, n> &comp) true if any element is true
-
template<Uint32 m, Uint32 n>
inline ComparisonMatrix<m, n> operator&&(const ComparisonMatrix<m, n> &lhs, const ComparisonMatrix<m, n> &rhs)
-
template<Uint32 m, Uint32 n>
inline ComparisonMatrix<m, n> operator||(const ComparisonMatrix<m, n> &lhs, const ComparisonMatrix<m, n> &rhs)
-
template<Uint32 m, Uint32 n>
inline ComparisonMatrix<m, n> operator!(const ComparisonMatrix<m, n> &unary)
-
template<BodyRange T, class Alloc>
void solveIslands(const T &bodies, const Alloc &alloc, World::Settings s, float dt, Profiler &profiler)
-
inline Transform operator*(const Rotation &r, const Translation &t)
-
inline Transform operator*(const Translation &t, const Rotation &r)
-
inline Transform operator*(const Transform &T, const Translation &t)
-
inline Transform operator*(const Translation &t, const Transform &T)
-
template<std::bidirectional_iterator Iter, Callable<bool(Iter)> GoesLeft>
Iter booleanSort(Iter begin, Iter end, GoesLeft goesLeft)
-
bool isNan(float val)
-
template<class T, class Alloc, class ...Args, std::enable_if_t<!std::is_array_v<T>, bool> = true>
UniquePtr<T> makeUnique(const Alloc &alloc, Args&&... args)
-
template<class T, class Alloc, class ...Args, std::enable_if_t<std::is_array_v<T> && std::extent_v<T> == 0, bool> = true>
UniquePtr<T> makeUnique(const Alloc &alloc, std::size_t size)
-
template<std::forward_iterator Iter, class Deref>
auto makeView(Iter begin, Iter end, Deref deref) Creates a view of [begin, end) and applies Deref(*Iter) to every dereferenced element.
Deref must return a reference, ie it should not create new objects.
Variables
-
constexpr float EPSILON = 1e-6f
- template<class T, Uint32 dim> concept VertexIterator = requires(T it) {{ *it } -> std::convertible_to<Vector<float, dim>>;} && std::forward_iterator<T>
Any iterator that dereferences to a vector of dimension dim.
- template<class T> concept VertexIterator2D = VertexIterator<T, 2>
Any iterator that dereferences to a Vertex.
- template<class T> concept Geometry = requires(T geo){{ geo.begin() } -> VertexIterator2D;{ geo.end() } -> VertexIterator2D;}
Any type that allows iterating over vertices.
- template<class F> concept ConstraintFunction = requires(F f,typename F::Value lambda,constProxies& proxies,float dt) {requires F::nBodies == 1 || F::nBodies == 2;typename F::Value;requires std::is_same_v<typename F::Value,Vector<float, F::dimension>>;typename F::Jacobian;requires std::is_same_v<typename F::Jacobian,Matrix<float, F::dimension, 6>>;{ f.eval(proxies) } -> std::same_as<typename F::Value>;{ f.bias(proxies) } -> std::same_as<typename F::Value>;{ f.jacobian(proxies) } -> std::same_as<typename F::Jacobian>;{ f.clampLambda(lambda, dt) } -> std::same_as<typename F::Value>;{ f.clampPositionLambda(lambda) } -> std::same_as<typename F::Value>;}
- template<class S> concept ConstraintSolver = requires(S s,Proxies& proxies,constProxies& cProxies,typename S::F f,float dt) {typename S::F;requires ConstraintFunction<typename S::F>;requires std::derived_from<S,ConstraintSolverBase<typename S::F>>;requires std::constructible_from<S,Bodies, typename S::F>;{ s.initSolve(cProxies, f) };{ s.warmstart(proxies, f, dt) };{ s.solveVelocity(proxies, f, dt) };{ s.solvePosition(proxies, f) };}
- template<class T> concept BodyRange = Range<T> && requires(T t) {{ *t.begin() } -> std::convertible_to<Body&>;}
- template<class F, class Signature> concept Callable = details::SignatureDecomposition<Signature>::template IsCallable<F>::value
- template<class F, class Signature> concept StrictCallable = details::SignatureDecomposition<Signature>::template IsCallableStrictReturn<F>::value
- template<class R> concept Range = std::ranges::range<R>
-
template<class T>
-
namespace details
Functions
- template<class Tuple, class Func, Uint32 i = 0> requires constexpr std::invocable< Func, std::tuple_element_t< i, Tuple > & > void forEach (Tuple &tuple, Func &func)
- template<class Tuple, class Func, Uint32 i = 0> requires constexpr std::invocable< Func, const std::tuple_element_t< i, Tuple > & > void forEach (const Tuple &tuple, Func &func)
-
namespace TransformView
-
namespace priv
-
namespace std
Unnamed Group
-
template<class T, simu::Uint32 m, simu::Uint32 n>
inline simu::Matrix<T, m, n> abs(const simu::Matrix<T, m, n> &mat)
-
template<class T, simu::Uint32 m, simu::Uint32 n>
inline simu::Matrix<T, m, n> round(const simu::Matrix<T, m, n> &mat)
-
template<class T, simu::Uint32 m, simu::Uint32 n>
- file app.hpp
- #include “Simu/physics.hpp”#include “Simu/app/Application.hpp”
- file Application.hpp
- #include “Simu/physics.hpp”#include “Simu/app/Scene.hpp”#include “Simu/app/Event.hpp”
- file Camera.hpp
- #include “Simu/config.hpp”#include “Simu/physics/BoundingBox.hpp”
- file Event.hpp
- #include “Simu/config.hpp”#include “Simu/math/Matrix.hpp”
- file MouseConstraint.hpp
- #include “Simu/physics/Constraint.hpp”
- file Renderer.hpp
- #include <vector>#include “Simu/config.hpp”#include “Simu/math/Geometry.hpp”#include “Simu/utility/View.hpp”#include “Simu/utility/Memory.hpp”
- file Scene.hpp
- #include “Simu/config.hpp”#include “Simu/physics.hpp”#include “Simu/utility/View.hpp”#include “Simu/app/Renderer.hpp”#include “Simu/app/Camera.hpp”#include “Simu/app/Event.hpp”#include “Simu/app/VisiblePhysics.hpp”#include “Simu/app/Tool.hpp”
- file Tool.hpp
- #include “Simu/app/Event.hpp”#include “Simu/app/VisiblePhysics.hpp”
- file VisiblePhysics.hpp
- #include “Simu/physics.hpp”#include “Simu/app/Renderer.hpp”#include “Simu/app/MouseConstraint.hpp”
- file config.hpp
- #include <cstdint>#include <exception>#include <sstream>
- file math.hpp
- #include “math/Matrix.hpp”#include “math/Interval.hpp”#include “math/Geometry.hpp”#include “math/BarycentricCoordinates.hpp”#include “math/Polygon.hpp”#include “math/Gjk.hpp”
- file BarycentricCoordinates.hpp
- #include “Simu/math/Matrix.hpp”#include “Simu/utility/Algo.hpp”
- file Edges.hpp
- #include “Simu/utility/Algo.hpp”#include “Simu/math/Geometry.hpp”#include “Simu/math/BarycentricCoordinates.hpp”
- file Geometry.hpp
- #include <concepts>#include <vector>#include “Simu/math/Matrix.hpp”#include “Simu/math/Interval.hpp”#include “Simu/math/Geometry.inl.hpp”
- file Geometry.inl.hpp
- #include “Simu/math/Geometry.hpp”#include “Simu/math/Edges.hpp”
- file Gjk.hpp
- #include <array>#include “Simu/math/Polygon.hpp”#include “Gjk.inl.hpp”
- file Gjk.inl.hpp
- #include “Simu/math/Gjk.hpp”#include “Simu/math/BarycentricCoordinates.hpp”
- file Interval.hpp
- #include “Simu/config.hpp”#include <cmath>
- file Matrix.hpp
- #include <initializer_list>#include <type_traits>#include <cmath>#include <optional>#include “Simu/config.hpp”#include “Simu/math/Matrix.inl.hpp”
- file Matrix.inl.hpp
- #include “Simu/math/Matrix.hpp”
- file Polygon.hpp
- #include <algorithm>#include “Simu/config.hpp”#include “Simu/math/Matrix.hpp”#include “Simu/math/Geometry.hpp”#include “Simu/utility/View.hpp”#include “Simu/math/Polygon.inl.hpp”
- file Polygon.inl.hpp
- #include “Simu/math/Polygon.hpp”
- file Random.hpp
- #include <random>#include <concepts>#include “Simu/config.hpp”
- file physics.hpp
- #include “Simu/math.hpp”#include “Simu/physics/World.hpp”#include “Simu/physics/Constraint.hpp”#include “Simu/physics/Motors.hpp”#include “Simu/physics/DistanceConstraint.hpp”
- file Bodies.hpp
- #include <cmath>#include <array>#include <optional>#include <ranges>#include “Simu/config.hpp”#include “Simu/physics/Body.hpp”#include “Simu/physics/Bodies.inl.hpp”
- file Bodies.inl.hpp
- #include “Simu/physics/Bodies.hpp”#include “Simu/physics/Body.hpp”
- file Body.hpp
- #include <type_traits>#include “Simu/config.hpp”#include “Simu/math/Matrix.hpp”#include “Simu/physics/PhysicsObject.hpp”#include “Simu/physics/BodyTree.hpp”#include “Simu/physics/Transform.hpp”#include “Simu/physics/Collider.hpp”#include “Simu/utility/View.hpp”
- file BodyTree.hpp
- #include “Simu/config.hpp”#include “Simu/physics/RTree.hpp”#include “Simu/utility/Memory.hpp”
- file BoundingBox.hpp
- #include “Simu/config.hpp”#include “Simu/math/Matrix.hpp”#include “Simu/math/Geometry.hpp”
- file Collider.hpp
- #include <list>#include “Simu/config.hpp”#include “Simu/math/Polygon.hpp”#include “Simu/physics/BoundingBox.hpp”#include “Simu/physics/Material.hpp”
- file CombinableProperty.hpp
- #include “Simu/config.hpp”
- file Constraint.hpp
- #include <memory>#include “Simu/math/Gjk.hpp”#include “Simu/physics/ContactManifold.hpp”#include “Simu/physics/Body.hpp”#include “Simu/physics/ConstraintFunction.hpp”#include “Simu/physics/ConstraintSolver.hpp”#include “Simu/physics/Constraint.inl.hpp”
- file Constraint.inl.hpp
- #include “Simu/physics/Constraint.hpp”#include “Simu/physics/World.hpp”
- file ConstraintFunction.hpp
- #include “Simu/config.hpp”#include “Simu/physics/Body.hpp”#include “Simu/physics/Bodies.hpp”#include “Simu/physics/ContactManifold.hpp”#include “Simu/physics/ConstraintInterfaces.hpp”
- file ConstraintInterfaces.hpp
- #include “Simu/utility/View.hpp”#include “Simu/math/Matrix.hpp”#include “Simu/physics/PhysicsObject.hpp”#include “Simu/physics/Bodies.hpp”
- file ConstraintSolver.hpp
- #include <iostream>#include “Simu/config.hpp”#include “Simu/math/Matrix.hpp”#include “Simu/physics/ConstraintInterfaces.hpp”
- file ContactManifold.hpp
- #include <algorithm>#include <array>#include “Simu/math/Gjk.hpp”#include “Simu/physics/Bodies.hpp”
- file DistanceConstraint.hpp
- #include “Simu/physics/Constraint.hpp”
- file ForceField.hpp
- #include “Simu/config.hpp”#include “Simu/physics/BoundingBox.hpp”#include “Simu/physics/Body.hpp”
- file Island.hpp
- #include <set>#include “Simu/physics/Body.hpp”#include “Simu/physics/Constraint.hpp”
- file Material.hpp
- #include “Simu/config.hpp”#include “Simu/physics/CombinableProperty.hpp”
- file Motors.hpp
- #include “Simu/config.hpp”#include “Simu/physics/Constraint.hpp”
- file PhysicsObject.hpp
- #include “Simu/config.hpp”#include “Simu/utility/Memory.hpp”
- file Profiler.hpp
- #include <chrono>#include “Simu/config.hpp”
- file RTree.hpp
- #include <queue>#include <utility>#include “Simu/config.hpp”#include “Simu/physics/BoundingBox.hpp”#include “Simu/utility/View.hpp”#include “Simu/utility/Algo.hpp”#include “Simu/utility/Callable.hpp”#include “Simu/utility/Memory.hpp”#include “Simu/physics/RTree.inl.hpp”
- file RTree.inl.hpp
- #include “Simu/physics/RTree.hpp”
- file Transform.hpp
- #include <cmath>#include <numbers>#include “Simu/config.hpp”#include “Simu/math/Matrix.hpp”
- file World.hpp
- #include “Simu/config.hpp”#include “Simu/utility/View.hpp”#include “Simu/utility/Memory.hpp”#include “Simu/physics/BodyTree.hpp”#include “Simu/physics/Body.hpp”#include “Simu/physics/Bodies.hpp”#include “Simu/physics/ForceField.hpp”#include “Simu/physics/Profiler.hpp”#include <list>#include <unordered_map>
- file Algo.hpp
- #include “Simu/utility/Callable.hpp”
- file Callable.hpp
- #include <functional>#include “Simu/config.hpp”
- file FloatingPointExceptions.hpp
- #include <float.h>#include <fenv.h>
- file Memory.hpp
- #include <cstdlib>#include <cstddef>#include <memory>#include <functional>#include <list>#include “Simu/config.hpp”
- file View.hpp
- #include <ranges>#include “Simu/utility/View.inl.hpp”
Defines
-
SIMU_HAS_STD_VIEW
-
SIMU_HAS_STD_VIEW
- file View.inl.hpp
- #include “Simu/utility/View.hpp”
- group math
Math classes and related algorithms for Simu.
- group BarycentricCoordinates
Barycentric coordinates allows finding the closest point on a line or triangle from a point Q.
For an intuitive explanation, see Erin Catto’s GDC conference, slides available at https://box2d.org/files/ErinCatto_GJK_GDC2010.pdf
- group Geometry
Typedefs
-
typedef Vec2 Vertex
Enums
Variables
- template<class T, Uint32 dim> concept VertexIterator = requires(T it) {{ *it } -> std::convertible_to<Vector<float, dim>>;} && std::forward_iterator<T>
Any iterator that dereferences to a vector of dimension dim.
- template<class T> concept VertexIterator2D = VertexIterator<T, 2>
Any iterator that dereferences to a Vertex.
- template<class T> concept Geometry = requires(T geo){{ geo.begin() } -> VertexIterator2D;{ geo.end() } -> VertexIterator2D;}
Any type that allows iterating over vertices.
-
typedef Vec2 Vertex
- group LinearAlgebra
- group operations
- group comparison
Typedefs
-
template<Uint32 m, Uint32 n>
using ComparisonMatrix = MatrixData<bool, m, n> Comparison Matrix returned by comparisons of matrices.
This is not convertible to bool, use the functions all() and any() to evaluate to a bool.
All matrix comparisons are done element-wise.
element-wise boolean operators are also provided for ComparisonMatrix
-
template<Uint32 m, Uint32 n>
- dir /home/runner/work/Simu/Simu/include/Simu/app
- dir /home/runner/work/Simu/Simu/include
- dir /home/runner/work/Simu/Simu/include/Simu/math
- dir /home/runner/work/Simu/Simu/include/Simu/physics
- dir /home/runner/work/Simu/Simu/include/Simu
- dir /home/runner/work/Simu/Simu/include/Simu/utility