33#ifndef DART_CONSTRAINT_CONSTRAINTSOVER_HPP_
34#define DART_CONSTRAINT_CONSTRAINTSOVER_HPP_
49class ShapeNodeCollisionObject;
73 void addSkeletons(
const std::vector<dynamics::SkeletonPtr>& skeletons);
79 void removeSkeletons(
const std::vector<dynamics::SkeletonPtr>& skeletons);
172 bool isSoftContact(const collision::Contact& _contact) const;
#define DART_DEPRECATED(version)
Definition Deprecated.hpp:51
Definition CollisionDetector.hpp:56
ConstrainedGroup is a group of skeletons that interact each other with constraints.
Definition ConstrainedGroup.hpp:58
ConstraintSolver manages constraints and computes constraint impulses.
Definition ConstraintSolver.hpp:56
std::vector< SoftContactConstraintPtr > mSoftContactConstraints
Soft contact constraints those are automatically created.
Definition ConstraintSolver.hpp:201
void removeSkeletons(const std::vector< dynamics::SkeletonPtr > &skeletons)
Remove multiple skeletons.
Definition ConstraintSolver.cpp:134
std::vector< dynamics::SkeletonPtr > mSkeletons
Skeleton list.
Definition ConstraintSolver.hpp:195
collision::CollisionResult mCollisionResult
Last collision checking result.
Definition ConstraintSolver.hpp:186
void addSkeletons(const std::vector< dynamics::SkeletonPtr > &skeletons)
Add mutiple skeletons.
Definition ConstraintSolver.cpp:108
void clearLastCollisionResult()
Clears the last collision result.
Definition ConstraintSolver.cpp:187
void removeAllConstraints()
Remove all constraints.
Definition ConstraintSolver.cpp:181
std::vector< JointCoulombFrictionConstraintPtr > mJointCoulombFrictionConstraints
Joint Coulomb friction constraints those are automatically created.
Definition ConstraintSolver.hpp:210
collision::CollisionGroupPtr getCollisionGroup()
Return collision group of collision objects that are added to this ConstraintSolver.
Definition ConstraintSolver.cpp:253
void solveConstrainedGroups()
Solve constrained groups.
Definition ConstraintSolver.cpp:596
std::vector< ContactConstraintPtr > mContactConstraints
Contact constraints those are automatically created.
Definition ConstraintSolver.hpp:198
void solve()
Solve constraint impulses and apply them to the skeletons.
Definition ConstraintSolver.cpp:304
void addSkeleton(const dynamics::SkeletonPtr &skeleton)
Add single skeleton.
Definition ConstraintSolver.cpp:88
collision::CollisionDetectorPtr mCollisionDetector
Collision detector.
Definition ConstraintSolver.hpp:177
bool checkAndAddSkeleton(const dynamics::SkeletonPtr &_skeleton)
Add skeleton if the constraint is not contained in this solver.
Definition ConstraintSolver.cpp:340
collision::CollisionDetectorPtr getCollisionDetector()
Get collision detector.
Definition ConstraintSolver.cpp:240
bool checkAndAddConstraint(const ConstraintBasePtr &_constraint)
Add constraint if the constraint is not contained in this solver.
Definition ConstraintSolver.cpp:365
double getTimeStep() const
Get time step.
Definition ConstraintSolver.cpp:203
void setTimeStep(double _timeStep)
Set time step.
Definition ConstraintSolver.cpp:193
void addConstraint(const ConstraintBasePtr &_constraint)
Add a constraint.
Definition ConstraintSolver.cpp:149
collision::CollisionOption & getCollisionOption()
Returns collision option that is used for collision checkings in this ConstraintSolver to generate co...
Definition ConstraintSolver.cpp:265
std::unique_ptr< LCPSolver > mLCPSolver
LCP solver.
Definition ConstraintSolver.hpp:192
std::vector< ServoMotorConstraintPtr > mServoMotorConstraints
Servo motor constraints those are automatically created.
Definition ConstraintSolver.hpp:207
void removeSkeleton(const dynamics::SkeletonPtr &skeleton)
Remove single skeleton.
Definition ConstraintSolver.cpp:115
bool isSoftContact(const collision::Contact &_contact) const
Return true if at least one of colliding body is soft body.
Definition ConstraintSolver.cpp:606
std::vector< ConstrainedGroup > mConstrainedGroups
Constraint group list.
Definition ConstraintSolver.hpp:219
bool containConstraint(const ConstConstraintBasePtr &_constraint) const
Check if the constraint is contained in this solver.
Definition ConstraintSolver.cpp:356
collision::CollisionResult & getLastCollisionResult()
Return the last collision checking result.
Definition ConstraintSolver.cpp:277
void removeConstraint(const ConstraintBasePtr &_constraint)
Remove a constraint.
Definition ConstraintSolver.cpp:164
ConstraintSolver(const ConstraintSolver &_other)=delete
Copy constructor.
std::vector< ConstraintBasePtr > mManualConstraints
Constraints that manually added.
Definition ConstraintSolver.hpp:213
collision::CollisionGroupPtr mCollisionGroup
Collision group.
Definition ConstraintSolver.hpp:180
std::vector< ConstraintBasePtr > mActiveConstraints
Active constraints.
Definition ConstraintSolver.hpp:216
bool containSkeleton(const dynamics::ConstSkeletonPtr &_skeleton) const
Check if the skeleton is contained in this solver.
Definition ConstraintSolver.cpp:325
double mTimeStep
Time step.
Definition ConstraintSolver.hpp:189
void removeAllSkeletons()
Remove all skeletons in this constraint solver.
Definition ConstraintSolver.cpp:142
virtual ~ConstraintSolver()
Destructor.
Definition ConstraintSolver.cpp:82
std::vector< JointLimitConstraintPtr > mJointLimitConstraints
Joint limit constraints those are automatically created.
Definition ConstraintSolver.hpp:204
void updateConstraints()
Update constraints.
Definition ConstraintSolver.cpp:381
collision::CollisionOption mCollisionOption
Collision detection option.
Definition ConstraintSolver.hpp:183
void setLCPSolver(std::unique_ptr< LCPSolver > _lcpSolver)
Set LCP solver.
Definition ConstraintSolver.cpp:290
LCPSolver * getLCPSolver() const
Get LCP solver.
Definition ConstraintSolver.cpp:298
void setCollisionDetector(collision::CollisionDetector *collisionDetector)
Set collision detector.
Definition ConstraintSolver.cpp:209
void buildConstrainedGroups()
Build constrained groupsContact.
Definition ConstraintSolver.cpp:530
LCPSolver.
Definition LCPSolver.hpp:43
std::shared_ptr< JointCoulombFrictionConstraint > JointCoulombFrictionConstraintPtr
Definition SmartPointer.hpp:48
std::shared_ptr< const ConstraintBase > ConstConstraintBasePtr
Definition SmartPointer.hpp:42
std::shared_ptr< ContactConstraint > ContactConstraintPtr
Definition SmartPointer.hpp:44
std::shared_ptr< ServoMotorConstraint > ServoMotorConstraintPtr
Definition SmartPointer.hpp:47
std::shared_ptr< JointLimitConstraint > JointLimitConstraintPtr
Definition SmartPointer.hpp:46
std::shared_ptr< ConstraintBase > ConstraintBasePtr
Definition SmartPointer.hpp:42
std::shared_ptr< SoftContactConstraint > SoftContactConstraintPtr
Definition SmartPointer.hpp:45
std::shared_ptr< const Skeleton > ConstSkeletonPtr
Definition SmartPointer.hpp:60
std::shared_ptr< Skeleton > SkeletonPtr
Definition SmartPointer.hpp:60
Definition BulletCollisionDetector.cpp:63
Definition SharedLibraryManager.hpp:43