33 #ifndef DART_CONSTRAINT_CONSTRAINTSOVER_HPP_
34 #define DART_CONSTRAINT_CONSTRAINTSOVER_HPP_
38 #include <Eigen/Dense>
50 class ShapeNodeCollisionObject;
53 namespace constraint {
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);
123 std::vector<constraint::ConstConstraintBasePtr>
getConstraints()
const;
#define DART_DEPRECATED(version)
Definition: Deprecated.hpp:51
std::size_t index
Definition: SkelParser.cpp:1672
Definition: CollisionDetector.hpp:58
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:57
std::vector< SoftContactConstraintPtr > mSoftContactConstraints
Soft contact constraints those are automatically created.
Definition: ConstraintSolver.hpp:239
void removeSkeletons(const std::vector< dynamics::SkeletonPtr > &skeletons)
Remove multiple skeletons.
Definition: ConstraintSolver.cpp:153
std::vector< dynamics::SkeletonPtr > mSkeletons
Skeleton list.
Definition: ConstraintSolver.hpp:233
std::vector< constraint::ConstraintBasePtr > getConstraints()
Returns all the constraints added to this ConstraintSolver.
Definition: ConstraintSolver.cpp:224
collision::CollisionResult mCollisionResult
Last collision checking result.
Definition: ConstraintSolver.hpp:227
void addSkeletons(const std::vector< dynamics::SkeletonPtr > &skeletons)
Add mutiple skeletons.
Definition: ConstraintSolver.cpp:120
void clearLastCollisionResult()
Clears the last collision result.
Definition: ConstraintSolver.cpp:244
void removeAllConstraints()
Remove all constraints.
Definition: ConstraintSolver.cpp:200
bool containConstraint(const ConstConstraintBasePtr &constraint) const
Check if the constraint is contained in this solver.
Definition: ConstraintSolver.cpp:429
virtual void solveConstrainedGroup(ConstrainedGroup &group)=0
std::vector< JointCoulombFrictionConstraintPtr > mJointCoulombFrictionConstraints
Joint Coulomb friction constraints those are automatically created.
Definition: ConstraintSolver.hpp:252
virtual ~ConstraintSolver()=default
Destructor.
void removeConstraint(const ConstraintBasePtr &constraint)
Remove a constraint.
Definition: ConstraintSolver.cpp:183
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:307
ConstraintSolver()
Default constructor.
Definition: ConstraintSolver.cpp:82
void solveConstrainedGroups()
Solve constrained groups.
Definition: ConstraintSolver.cpp:733
std::vector< ContactConstraintPtr > mContactConstraints
Contact constraints those are automatically created.
Definition: ConstraintSolver.hpp:236
bool checkAndAddSkeleton(const dynamics::SkeletonPtr &skeleton)
Add skeleton if the constraint is not contained in this solver.
Definition: ConstraintSolver.cpp:413
void solve()
Solve constraint impulses and apply them to the skeletons.
Definition: ConstraintSolver.cpp:364
virtual void setFromOtherConstraintSolver(const ConstraintSolver &other)
Sets this constraint solver using other constraint solver.
Definition: ConstraintSolver.cpp:385
std::size_t getNumConstraints() const
Returns the number of constraints that was manually added to this ConstraintSolver.
Definition: ConstraintSolver.cpp:206
void addSkeleton(const dynamics::SkeletonPtr &skeleton)
Add single skeleton.
Definition: ConstraintSolver.cpp:99
collision::CollisionDetectorPtr mCollisionDetector
Collision detector.
Definition: ConstraintSolver.hpp:218
constraint::ConstraintBasePtr getConstraint(std::size_t index)
Returns a constraint by index.
Definition: ConstraintSolver.cpp:212
bool checkAndAddConstraint(const ConstraintBasePtr &constraint)
Add constraint if the constraint is not contained in this solver.
Definition: ConstraintSolver.cpp:438
void addConstraint(const ConstraintBasePtr &constraint)
Add a constraint.
Definition: ConstraintSolver.cpp:168
collision::CollisionDetectorPtr getCollisionDetector()
Get collision detector.
Definition: ConstraintSolver.cpp:294
double getTimeStep() const
Get time step.
Definition: ConstraintSolver.cpp:257
virtual void setTimeStep(double _timeStep)
Set time step.
Definition: ConstraintSolver.cpp:250
collision::CollisionOption & getCollisionOption()
Returns collision option that is used for collision checkings in this ConstraintSolver to generate co...
Definition: ConstraintSolver.cpp:319
std::vector< MimicMotorConstraintPtr > mMimicMotorConstraints
Mimic motor constraints those are automatically created.
Definition: ConstraintSolver.hpp:248
std::vector< ServoMotorConstraintPtr > mServoMotorConstraints
Servo motor constraints those are automatically created.
Definition: ConstraintSolver.hpp:245
void removeSkeleton(const dynamics::SkeletonPtr &skeleton)
Remove single skeleton.
Definition: ConstraintSolver.cpp:133
std::vector< ConstrainedGroup > mConstrainedGroups
Constraint group list.
Definition: ConstraintSolver.hpp:261
collision::CollisionResult & getLastCollisionResult()
Return the last collision checking result.
Definition: ConstraintSolver.cpp:331
std::vector< ConstraintBasePtr > mManualConstraints
Constraints that manually added.
Definition: ConstraintSolver.hpp:255
const std::vector< dynamics::SkeletonPtr > & getSkeletons() const
Returns all the skeletons added to this ConstraintSolver.
Definition: ConstraintSolver.cpp:127
collision::CollisionGroupPtr mCollisionGroup
Collision group.
Definition: ConstraintSolver.hpp:221
std::vector< ConstraintBasePtr > mActiveConstraints
Active constraints.
Definition: ConstraintSolver.hpp:258
bool isSoftContact(const collision::Contact &contact) const
Return true if at least one of colliding body is soft body.
Definition: ConstraintSolver.cpp:740
double mTimeStep
Time step.
Definition: ConstraintSolver.hpp:230
void setLCPSolver(std::unique_ptr< LCPSolver > lcpSolver)
Set LCP solver.
Definition: ConstraintSolver.cpp:344
void removeAllSkeletons()
Remove all skeletons in this constraint solver.
Definition: ConstraintSolver.cpp:161
std::vector< JointLimitConstraintPtr > mJointLimitConstraints
Joint limit constraints those are automatically created.
Definition: ConstraintSolver.hpp:242
void updateConstraints()
Update constraints.
Definition: ConstraintSolver.cpp:454
collision::CollisionOption mCollisionOption
Collision detection option.
Definition: ConstraintSolver.hpp:224
bool containSkeleton(const dynamics::ConstSkeletonPtr &skeleton) const
Check if the skeleton is contained in this solver.
Definition: ConstraintSolver.cpp:396
LCPSolver * getLCPSolver() const
Get LCP solver.
Definition: ConstraintSolver.cpp:353
void setCollisionDetector(collision::CollisionDetector *collisionDetector)
Set collision detector.
Definition: ConstraintSolver.cpp:263
void buildConstrainedGroups()
Build constrained groupsContact.
Definition: ConstraintSolver.cpp:677
Definition: LCPSolver.hpp:45
::fcl::CollisionResult CollisionResult
Definition: BackwardCompatibility.hpp:166
::fcl::Contact Contact
Definition: BackwardCompatibility.hpp:169
std::shared_ptr< const CollisionDetector > ConstCollisionDetectorPtr
Definition: SmartPointer.hpp:41
std::shared_ptr< CollisionDetector > CollisionDetectorPtr
Definition: SmartPointer.hpp:41
std::shared_ptr< const CollisionGroup > ConstCollisionGroupPtr
Definition: SmartPointer.hpp:46
std::shared_ptr< CollisionGroup > CollisionGroupPtr
Definition: SmartPointer.hpp:46
std::shared_ptr< JointCoulombFrictionConstraint > JointCoulombFrictionConstraintPtr
Definition: SmartPointer.hpp:52
std::shared_ptr< const ConstraintBase > ConstConstraintBasePtr
Definition: SmartPointer.hpp:45
std::shared_ptr< ContactConstraint > ContactConstraintPtr
Definition: SmartPointer.hpp:47
std::shared_ptr< MimicMotorConstraint > MimicMotorConstraintPtr
Definition: SmartPointer.hpp:51
std::shared_ptr< ServoMotorConstraint > ServoMotorConstraintPtr
Definition: SmartPointer.hpp:50
std::shared_ptr< JointLimitConstraint > JointLimitConstraintPtr
Definition: SmartPointer.hpp:49
std::shared_ptr< ConstraintBase > ConstraintBasePtr
Definition: SmartPointer.hpp:45
std::shared_ptr< SoftContactConstraint > SoftContactConstraintPtr
Definition: SmartPointer.hpp:48
std::shared_ptr< const Skeleton > ConstSkeletonPtr
Definition: SmartPointer.hpp:60
std::shared_ptr< Skeleton > SkeletonPtr
Definition: SmartPointer.hpp:60
Definition: BulletCollisionDetector.cpp:65
Definition: SharedLibraryManager.hpp:46