33 #ifndef DART_CONSTRAINT_CONSTRAINTSOVER_HPP_ 34 #define DART_CONSTRAINT_CONSTRAINTSOVER_HPP_ 38 #include <Eigen/Dense> 40 #include "dart/common/Deprecated.hpp" 41 #include "dart/dynamics/CollisionDetector.hpp" 42 #include "dart/dynamics/ConstrainedGroup.hpp" 43 #include "dart/dynamics/ConstraintBase.hpp" 44 #include "dart/dynamics/SmartPointer.hpp" 50 class ShapeNodeCollisionObject;
83 void addSkeleton(
const dynamics::SkeletonPtr& skeleton);
86 void addSkeletons(
const std::vector<dynamics::SkeletonPtr>& skeletons);
89 const std::vector<dynamics::SkeletonPtr>& getSkeletons()
const;
92 void removeSkeleton(
const dynamics::SkeletonPtr& skeleton);
95 void removeSkeletons(
const std::vector<dynamics::SkeletonPtr>& skeletons);
98 void removeAllSkeletons();
101 void addConstraint(
const ConstraintBasePtr& constraint);
104 void removeConstraint(
const ConstraintBasePtr& constraint);
107 void removeAllConstraints();
111 std::size_t getNumConstraints()
const;
114 dynamics::ConstraintBasePtr getConstraint(std::size_t index);
117 dynamics::ConstConstraintBasePtr getConstraint(std::size_t index)
const;
120 std::vector<dynamics::ConstraintBasePtr> getConstraints();
123 std::vector<dynamics::ConstConstraintBasePtr> getConstraints()
const;
126 void clearLastCollisionResult();
129 virtual void setTimeStep(
double _timeStep);
132 double getTimeStep()
const;
141 void setCollisionDetector(
142 const std::shared_ptr<collision::CollisionDetector>& collisionDetector);
145 collision::CollisionDetectorPtr getCollisionDetector();
148 collision::ConstCollisionDetectorPtr getCollisionDetector()
const;
152 collision::CollisionGroupPtr getCollisionGroup();
156 collision::ConstCollisionGroupPtr getCollisionGroup()
const;
174 void setLCPSolver(std::unique_ptr<LCPSolver> lcpSolver);
192 bool containSkeleton(
const dynamics::ConstSkeletonPtr& skeleton)
const;
195 bool checkAndAddSkeleton(
const dynamics::SkeletonPtr& skeleton);
198 bool containConstraint(
const ConstConstraintBasePtr& constraint)
const;
201 bool checkAndAddConstraint(
const ConstraintBasePtr& constraint);
204 void updateConstraints();
207 void buildConstrainedGroups();
210 void solveConstrainedGroups();
251 std::vector<JointCoulombFrictionConstraintPtr>
267 #endif // DART_CONSTRAINT_CONSTRAINTSOVER_HPP_ ConstrainedGroup is a group of skeletons that interact each other with constraints.
Definition: ConstrainedGroup.hpp:57
Definition: LCPSolver.hpp:44
collision::CollisionOption mCollisionOption
Collision detection option.
Definition: ConstraintSolver.hpp:224
ConstraintSolver manages constraints and computes constraint impulses.
Definition: ConstraintSolver.hpp:56
std::vector< ConstraintBasePtr > mActiveConstraints
Active constraints.
Definition: ConstraintSolver.hpp:258
std::vector< MimicMotorConstraintPtr > mMimicMotorConstraints
Mimic motor constraints those are automatically created.
Definition: ConstraintSolver.hpp:248
Definition: Aspect.cpp:40
collision::CollisionResult mCollisionResult
Last collision checking result.
Definition: ConstraintSolver.hpp:227
double mTimeStep
Time step.
Definition: ConstraintSolver.hpp:230
Definition: CollisionOption.hpp:44
std::vector< ContactConstraintPtr > mContactConstraints
Contact constraints those are automatically created.
Definition: ConstraintSolver.hpp:236
std::vector< ConstrainedGroup > mConstrainedGroups
Constraint group list.
Definition: ConstraintSolver.hpp:261
Definition: CollisionResult.hpp:51
std::vector< SoftContactConstraintPtr > mSoftContactConstraints
Soft contact constraints those are automatically created.
Definition: ConstraintSolver.hpp:239
collision::CollisionDetectorPtr mCollisionDetector
Collision detector.
Definition: ConstraintSolver.hpp:218
collision::CollisionGroupPtr mCollisionGroup
Collision group.
Definition: ConstraintSolver.hpp:221
std::vector< dynamics::SkeletonPtr > mSkeletons
Skeleton list.
Definition: ConstraintSolver.hpp:233
std::vector< JointLimitConstraintPtr > mJointLimitConstraints
Joint limit constraints those are automatically created.
Definition: ConstraintSolver.hpp:242
std::vector< ConstraintBasePtr > mManualConstraints
Constraints that manually added.
Definition: ConstraintSolver.hpp:255
Definition: CollisionDetector.hpp:56
std::vector< JointCoulombFrictionConstraintPtr > mJointCoulombFrictionConstraints
Joint Coulomb friction constraints those are automatically created.
Definition: ConstraintSolver.hpp:252
std::vector< ServoMotorConstraintPtr > mServoMotorConstraints
Servo motor constraints those are automatically created.
Definition: ConstraintSolver.hpp:245