b2_contact_solver.h
Go to the documentation of this file.
1 // MIT License
2 
3 // Copyright (c) 2019 Erin Catto
4 
5 // Permission is hereby granted, free of charge, to any person obtaining a copy
6 // of this software and associated documentation files (the "Software"), to deal
7 // in the Software without restriction, including without limitation the rights
8 // to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
9 // copies of the Software, and to permit persons to whom the Software is
10 // furnished to do so, subject to the following conditions:
11 
12 // The above copyright notice and this permission notice shall be included in all
13 // copies or substantial portions of the Software.
14 
15 // THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
16 // IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
17 // FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
18 // AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
19 // LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
20 // OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
21 // SOFTWARE.
22 
23 #ifndef B2_CONTACT_SOLVER_H
24 #define B2_CONTACT_SOLVER_H
25 
26 #include "box2d/b2_collision.h"
27 #include "box2d/b2_math.h"
28 #include "box2d/b2_time_step.h"
29 
30 class b2Contact;
31 class b2Body;
32 class b2StackAllocator;
34 
36 {
41  float normalMass;
42  float tangentMass;
43  float velocityBias;
44 };
45 
47 {
55  float invIA, invIB;
56  float friction;
57  float restitution;
58  float threshold;
59  float tangentSpeed;
62 };
63 
65 {
72 };
73 
75 {
76 public:
79 
81 
82  void WarmStart();
84  void StoreImpulses();
85 
87  bool SolveTOIPositionConstraints(int32 toiIndexA, int32 toiIndexB);
88 
96  int m_count;
97 };
98 
99 #endif
100 
b2ContactVelocityConstraint
Definition: b2_contact_solver.h:46
b2ContactVelocityConstraint::invIB
float invIB
Definition: b2_contact_solver.h:55
b2ContactVelocityConstraint::threshold
float threshold
Definition: b2_contact_solver.h:58
b2ContactSolver::b2ContactSolver
b2ContactSolver(b2ContactSolverDef *def)
Definition: b2_contact_solver.cpp:51
b2ContactSolver::SolveTOIPositionConstraints
bool SolveTOIPositionConstraints(int32 toiIndexA, int32 toiIndexB)
Definition: b2_contact_solver.cpp:755
b2VelocityConstraintPoint::normalMass
float normalMass
Definition: b2_contact_solver.h:41
b2StackAllocator
Definition: b2_stack_allocator.h:42
b2ContactVelocityConstraint::normal
b2Vec2 normal
Definition: b2_contact_solver.h:49
b2ContactSolverDef::positions
b2Position * positions
Definition: b2_contact_solver.h:69
b2ContactSolverDef::contacts
b2Contact ** contacts
Definition: b2_contact_solver.h:67
b2Mat22
A 2-by-2 matrix. Stored in column-major order.
Definition: b2_math.h:171
b2Body
A rigid body. These are created via b2World::CreateBody.
Definition: b2_body.h:128
b2ContactVelocityConstraint::friction
float friction
Definition: b2_contact_solver.h:56
b2_math.h
b2ContactVelocityConstraint::pointCount
int32 pointCount
Definition: b2_contact_solver.h:60
b2ContactSolver::m_count
int m_count
Definition: b2_contact_solver.h:96
b2ContactVelocityConstraint::indexB
int32 indexB
Definition: b2_contact_solver.h:53
b2Vec2
A 2D column vector.
Definition: b2_math.h:41
b2ContactSolver::m_velocities
b2Velocity * m_velocities
Definition: b2_contact_solver.h:91
b2ContactSolver::m_positionConstraints
b2ContactPositionConstraint * m_positionConstraints
Definition: b2_contact_solver.h:93
b2ContactSolverDef::allocator
b2StackAllocator * allocator
Definition: b2_contact_solver.h:71
b2ContactVelocityConstraint::indexA
int32 indexA
Definition: b2_contact_solver.h:52
b2Velocity
This is an internal structure.
Definition: b2_time_step.h:60
b2VelocityConstraintPoint
Definition: b2_contact_solver.h:35
b2ContactSolver::m_velocityConstraints
b2ContactVelocityConstraint * m_velocityConstraints
Definition: b2_contact_solver.h:94
b2ContactSolverDef
Definition: b2_contact_solver.h:64
b2VelocityConstraintPoint::normalImpulse
float normalImpulse
Definition: b2_contact_solver.h:39
b2Position
This is an internal structure.
Definition: b2_time_step.h:53
b2ContactVelocityConstraint::invIA
float invIA
Definition: b2_contact_solver.h:55
b2ContactVelocityConstraint::normalMass
b2Mat22 normalMass
Definition: b2_contact_solver.h:50
b2Contact
Definition: b2_contact.h:88
b2_maxManifoldPoints
#define b2_maxManifoldPoints
Definition: b2_common.h:51
b2ContactSolver::SolvePositionConstraints
bool SolvePositionConstraints()
Definition: b2_contact_solver.cpp:676
b2ContactVelocityConstraint::contactIndex
int32 contactIndex
Definition: b2_contact_solver.h:61
b2ContactSolver::StoreImpulses
void StoreImpulses()
Definition: b2_contact_solver.cpp:609
b2VelocityConstraintPoint::velocityBias
float velocityBias
Definition: b2_contact_solver.h:43
b2ContactVelocityConstraint::invMassB
float invMassB
Definition: b2_contact_solver.h:54
b2_collision.h
b2ContactPositionConstraint
Definition: b2_contact_solver.cpp:36
b2ContactVelocityConstraint::points
b2VelocityConstraintPoint points[b2_maxManifoldPoints]
Definition: b2_contact_solver.h:48
b2ContactSolverDef::count
int32 count
Definition: b2_contact_solver.h:68
b2ContactVelocityConstraint::restitution
float restitution
Definition: b2_contact_solver.h:57
b2ContactSolver::~b2ContactSolver
~b2ContactSolver()
Definition: b2_contact_solver.cpp:139
b2ContactSolver::WarmStart
void WarmStart()
Definition: b2_contact_solver.cpp:257
b2VelocityConstraintPoint::rA
b2Vec2 rA
Definition: b2_contact_solver.h:37
b2ContactSolver::m_step
b2TimeStep m_step
Definition: b2_contact_solver.h:89
b2ContactSolver::InitializeVelocityConstraints
void InitializeVelocityConstraints()
Definition: b2_contact_solver.cpp:146
b2ContactSolverDef::velocities
b2Velocity * velocities
Definition: b2_contact_solver.h:70
b2ContactVelocityConstraint::invMassA
float invMassA
Definition: b2_contact_solver.h:54
b2TimeStep
This is an internal structure.
Definition: b2_time_step.h:42
b2VelocityConstraintPoint::tangentMass
float tangentMass
Definition: b2_contact_solver.h:42
b2_time_step.h
int32
signed int int32
Definition: b2_types.h:28
b2ContactSolver::m_positions
b2Position * m_positions
Definition: b2_contact_solver.h:90
b2ContactSolver::m_allocator
b2StackAllocator * m_allocator
Definition: b2_contact_solver.h:92
b2VelocityConstraintPoint::rB
b2Vec2 rB
Definition: b2_contact_solver.h:38
b2ContactSolver::m_contacts
b2Contact ** m_contacts
Definition: b2_contact_solver.h:95
b2ContactSolverDef::step
b2TimeStep step
Definition: b2_contact_solver.h:66
b2ContactVelocityConstraint::K
b2Mat22 K
Definition: b2_contact_solver.h:51
b2ContactSolver
Definition: b2_contact_solver.h:74
b2ContactSolver::SolveVelocityConstraints
void SolveVelocityConstraints()
Definition: b2_contact_solver.cpp:297
b2ContactVelocityConstraint::tangentSpeed
float tangentSpeed
Definition: b2_contact_solver.h:59
b2VelocityConstraintPoint::tangentImpulse
float tangentImpulse
Definition: b2_contact_solver.h:40


mvsim
Author(s):
autogenerated on Wed May 28 2025 02:13:07