33#ifndef DART_CONSTRAINT_CONSTRAINTSOVER_HPP_
34#define DART_CONSTRAINT_CONSTRAINTSOVER_HPP_
50class ShapeNodeCollisionObject;
86 void addSkeletons(
const std::vector<dynamics::SkeletonPtr>& skeletons);
89 const std::vector<dynamics::SkeletonPtr>&
getSkeletons()
const;
95 void removeSkeletons(
const std::vector<dynamics::SkeletonPtr>& skeletons);
140 template <typename Func>
152 template <typename Func>
321#include "dart/constraint/detail/ConstraintSolver-impl.hpp"
#define DART_DEPRECATED(version)
Definition Deprecated.hpp:51
std::size_t index
Definition SkelParser.cpp:1673
Definition CollisionDetector.hpp:58
ConstrainedGroup is a group of skeletons that interact each other with constraints.
Definition ConstrainedGroup.hpp:59
ConstraintSolver manages constraints and computes constraint impulses.
Definition ConstraintSolver.hpp:57
std::vector< SoftContactConstraintPtr > mSoftContactConstraints
Soft contact constraints those are automatically created.
Definition ConstraintSolver.hpp:293
ContactSurfaceHandlerPtr getLastContactSurfaceHandler() const
Get the handler used for computing contact surface parameters based on the contact properties of the ...
Definition ConstraintSolver.cpp:752
void removeSkeletons(const std::vector< dynamics::SkeletonPtr > &skeletons)
Remove multiple skeletons.
Definition ConstraintSolver.cpp:156
std::vector< dynamics::SkeletonPtr > mSkeletons
Skeleton list.
Definition ConstraintSolver.hpp:287
std::vector< constraint::ConstraintBasePtr > getConstraints()
Returns all the constraints added to this ConstraintSolver.
Definition ConstraintSolver.cpp:227
collision::CollisionResult mCollisionResult
Last collision checking result.
Definition ConstraintSolver.hpp:281
void addSkeletons(const std::vector< dynamics::SkeletonPtr > &skeletons)
Add mutiple skeletons.
Definition ConstraintSolver.cpp:123
void clearLastCollisionResult()
Clears the last collision result.
Definition ConstraintSolver.cpp:247
void removeAllConstraints()
Remove all constraints.
Definition ConstraintSolver.cpp:203
void addContactSurfaceHandler(ContactSurfaceHandlerPtr handler)
Set the handler used for computing contact surface parameters based on the contact properties of the ...
Definition ConstraintSolver.cpp:758
bool containConstraint(const ConstConstraintBasePtr &constraint) const
Check if the constraint is contained in this solver.
Definition ConstraintSolver.cpp:443
virtual void solveConstrainedGroup(ConstrainedGroup &group)=0
std::vector< JointCoulombFrictionConstraintPtr > mJointCoulombFrictionConstraints
Joint Coulomb friction constraints those are automatically created.
Definition ConstraintSolver.hpp:303
virtual ~ConstraintSolver()=default
Destructor.
void removeConstraint(const ConstraintBasePtr &constraint)
Remove a constraint.
Definition ConstraintSolver.cpp:186
ConstraintSolver(const ConstraintSolver &other)=delete
Copy constructor.
collision::CollisionGroupPtr getCollisionGroup()
Return collision group of collision objects that are added to this ConstraintSolver.
Definition ConstraintSolver.cpp:310
ConstraintSolver()
Default constructor.
Definition ConstraintSolver.cpp:84
void solveConstrainedGroups()
Solve constrained groups.
Definition ConstraintSolver.cpp:725
std::vector< ContactConstraintPtr > mContactConstraints
Contact constraints those are automatically created.
Definition ConstraintSolver.hpp:290
bool checkAndAddSkeleton(const dynamics::SkeletonPtr &skeleton)
Add skeleton if the constraint is not contained in this solver.
Definition ConstraintSolver.cpp:427
void solve()
Solve constraint impulses and apply them to the skeletons.
Definition ConstraintSolver.cpp:367
virtual void setFromOtherConstraintSolver(const ConstraintSolver &other)
Sets this constraint solver using other constraint solver.
Definition ConstraintSolver.cpp:388
std::size_t getNumConstraints() const
Returns the number of constraints that was manually added to this ConstraintSolver.
Definition ConstraintSolver.cpp:209
void addSkeleton(const dynamics::SkeletonPtr &skeleton)
Add single skeleton.
Definition ConstraintSolver.cpp:102
collision::CollisionDetectorPtr mCollisionDetector
Collision detector.
Definition ConstraintSolver.hpp:272
constraint::ConstraintBasePtr getConstraint(std::size_t index)
Returns a constraint by index.
Definition ConstraintSolver.cpp:215
bool checkAndAddConstraint(const ConstraintBasePtr &constraint)
Add constraint if the constraint is not contained in this solver.
Definition ConstraintSolver.cpp:452
void addConstraint(const ConstraintBasePtr &constraint)
Add a constraint.
Definition ConstraintSolver.cpp:171
std::vector< JointConstraintPtr > mJointConstraints
Joint limit constraints those are automatically created.
Definition ConstraintSolver.hpp:296
collision::CollisionDetectorPtr getCollisionDetector()
Get collision detector.
Definition ConstraintSolver.cpp:297
ContactSurfaceHandlerPtr mContactSurfaceHandler
Factory for ContactSurfaceParams for each contact.
Definition ConstraintSolver.hpp:315
double getTimeStep() const
Get time step.
Definition ConstraintSolver.cpp:260
virtual void setTimeStep(double _timeStep)
Set time step.
Definition ConstraintSolver.cpp:253
bool hasSkeleton(const dynamics::ConstSkeletonPtr &skeleton) const
Checks if the skeleton is contained in this solver.
Definition ConstraintSolver.cpp:407
collision::CollisionOption & getCollisionOption()
Returns collision option that is used for collision checkings in this ConstraintSolver to generate co...
Definition ConstraintSolver.cpp:322
std::vector< MimicMotorConstraintPtr > mMimicMotorConstraints
Mimic motor constraints those are automatically created.
Definition ConstraintSolver.hpp:299
void removeSkeleton(const dynamics::SkeletonPtr &skeleton)
Remove single skeleton.
Definition ConstraintSolver.cpp:136
std::vector< ConstrainedGroup > mConstrainedGroups
Constraint group list.
Definition ConstraintSolver.hpp:312
collision::CollisionResult & getLastCollisionResult()
Return the last collision checking result.
Definition ConstraintSolver.cpp:334
std::vector< ConstraintBasePtr > mManualConstraints
Constraints that manually added.
Definition ConstraintSolver.hpp:306
const std::vector< dynamics::SkeletonPtr > & getSkeletons() const
Returns all the skeletons added to this ConstraintSolver.
Definition ConstraintSolver.cpp:130
collision::CollisionGroupPtr mCollisionGroup
Collision group.
Definition ConstraintSolver.hpp:275
std::vector< ConstraintBasePtr > mActiveConstraints
Active constraints.
Definition ConstraintSolver.hpp:309
bool isSoftContact(const collision::Contact &contact) const
Return true if at least one of colliding body is soft body.
Definition ConstraintSolver.cpp:732
double mTimeStep
Time step.
Definition ConstraintSolver.hpp:284
void setLCPSolver(std::unique_ptr< LCPSolver > lcpSolver)
Set LCP solver.
Definition ConstraintSolver.cpp:347
void removeAllSkeletons()
Remove all skeletons in this constraint solver.
Definition ConstraintSolver.cpp:164
bool removeContactSurfaceHandler(const ContactSurfaceHandlerPtr &handler)
Remove the given contact surface handler.
Definition ConstraintSolver.cpp:773
void updateConstraints()
Update constraints.
Definition ConstraintSolver.cpp:468
void eachConstraint(Func func) const
Iterates all the constraints and invokes the callback function.
Definition ConstraintSolver-impl.hpp:42
collision::CollisionOption mCollisionOption
Collision detection option.
Definition ConstraintSolver.hpp:278
bool containSkeleton(const dynamics::ConstSkeletonPtr &skeleton) const
Checks if the skeleton is contained in this solver.
Definition ConstraintSolver.cpp:401
LCPSolver * getLCPSolver() const
Get LCP solver.
Definition ConstraintSolver.cpp:356
void setCollisionDetector(collision::CollisionDetector *collisionDetector)
Set collision detector.
Definition ConstraintSolver.cpp:266
void buildConstrainedGroups()
Build constrained groupsContact.
Definition ConstraintSolver.cpp:669
Definition LCPSolver.hpp:45
std::shared_ptr< JointCoulombFrictionConstraint > JointCoulombFrictionConstraintPtr
Definition SmartPointer.hpp:52
std::shared_ptr< const ConstraintBase > ConstConstraintBasePtr
Definition SmartPointer.hpp:45
std::shared_ptr< ContactSurfaceHandler > ContactSurfaceHandlerPtr
Definition SmartPointer.hpp:48
std::shared_ptr< ContactConstraint > ContactConstraintPtr
Definition SmartPointer.hpp:47
std::shared_ptr< MimicMotorConstraint > MimicMotorConstraintPtr
Definition SmartPointer.hpp:51
std::shared_ptr< ConstraintBase > ConstraintBasePtr
Definition SmartPointer.hpp:45
std::shared_ptr< SoftContactConstraint > SoftContactConstraintPtr
Definition SmartPointer.hpp:49
std::shared_ptr< JointConstraint > JointConstraintPtr
Definition SmartPointer.hpp:50
std::shared_ptr< const Skeleton > ConstSkeletonPtr
Definition SmartPointer.hpp:60
std::shared_ptr< Skeleton > SkeletonPtr
Definition SmartPointer.hpp:60
Definition BulletCollisionDetector.cpp:60