DART  6.7.3
ConstraintSolver.hpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2011-2019, The DART development contributors
3  * All rights reserved.
4  *
5  * The list of contributors can be found at:
6  * https://github.com/dartsim/dart/blob/master/LICENSE
7  *
8  * This file is provided under the following "BSD-style" License:
9  * Redistribution and use in source and binary forms, with or
10  * without modification, are permitted provided that the following
11  * conditions are met:
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
19  * CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
20  * INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
21  * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
22  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
23  * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
24  * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
25  * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF
26  * USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  */
32 
33 #ifndef DART_CONSTRAINT_CONSTRAINTSOVER_HPP_
34 #define DART_CONSTRAINT_CONSTRAINTSOVER_HPP_
35 
36 #include <vector>
37 
38 #include <Eigen/Dense>
39 
44 
45 namespace dart {
46 
47 namespace dynamics {
48 class Skeleton;
49 class ShapeNodeCollisionObject;
50 } // namespace dynamics
51 
52 namespace constraint {
53 
56 {
57 public:
59  explicit ConstraintSolver(double timeStep);
60  // TODO(JS): Remove timeStep. The timestep can be set by world when a
61  // constraint solver is assigned to a world.
62 
64  // TODO: implement copy constructor since this class contains a pointer to
65  // allocated memory.
66  ConstraintSolver(const ConstraintSolver& other) = delete;
67 
69  virtual ~ConstraintSolver();
70 
72  void addSkeleton(const dynamics::SkeletonPtr& skeleton);
73 
75  void addSkeletons(const std::vector<dynamics::SkeletonPtr>& skeletons);
76 
78  const std::vector<dynamics::SkeletonPtr>& getSkeletons() const;
79 
81  void removeSkeleton(const dynamics::SkeletonPtr& skeleton);
82 
84  void removeSkeletons(const std::vector<dynamics::SkeletonPtr>& skeletons);
85 
87  void removeAllSkeletons();
88 
90  void addConstraint(const ConstraintBasePtr& constraint);
91 
93  void removeConstraint(const ConstraintBasePtr& constraint);
94 
96  void removeAllConstraints();
97 
100 
102  void setTimeStep(double _timeStep);
103 
105  double getTimeStep() const;
106 
110  DART_DEPRECATED(6.0)
111  void setCollisionDetector(collision::CollisionDetector* collisionDetector);
112 
115  const std::shared_ptr<collision::CollisionDetector>& collisionDetector);
116 
119 
122 
126 
129  collision::ConstCollisionGroupPtr getCollisionGroup() const;
130 
133  collision::CollisionOption& getCollisionOption();
134 
137  const collision::CollisionOption& getCollisionOption() const;
138 
141 
143  const collision::CollisionResult& getLastCollisionResult() const;
144 
146  DART_DEPRECATED(6.7)
147  void setLCPSolver(std::unique_ptr<LCPSolver> lcpSolver);
148 
150  DART_DEPRECATED(6.7)
151  LCPSolver* getLCPSolver() const;
152 
154  void solve();
155 
156 protected:
157  // TODO(JS): Docstring
158  virtual void solveConstrainedGroup(ConstrainedGroup& group) = 0;
159 
161  bool containSkeleton(const dynamics::ConstSkeletonPtr& skeleton) const;
162 
164  bool checkAndAddSkeleton(const dynamics::SkeletonPtr& skeleton);
165 
167  bool containConstraint(const ConstConstraintBasePtr& constraint) const;
168 
170  bool checkAndAddConstraint(const ConstraintBasePtr& constraint);
171 
173  void updateConstraints();
174 
176  void buildConstrainedGroups();
177 
179  void solveConstrainedGroups();
180 
182  bool isSoftContact(const collision::Contact& contact) const;
183 
185 
188 
191 
193  collision::CollisionOption mCollisionOption;
194 
197 
199  double mTimeStep;
200 
202  std::vector<dynamics::SkeletonPtr> mSkeletons;
203 
206 
209 
212 
215 
218 
221 
224 
227 
230 };
231 
232 } // namespace constraint
233 } // namespace dart
234 
235 #endif // DART_CONSTRAINT_CONSTRAINTSOVER_HPP_
#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:208
void removeSkeletons(const std::vector< dynamics::SkeletonPtr > &skeletons)
Remove multiple skeletons.
Definition: ConstraintSolver.cpp:139
std::vector< dynamics::SkeletonPtr > mSkeletons
Skeleton list.
Definition: ConstraintSolver.hpp:202
collision::CollisionResult mCollisionResult
Last collision checking result.
Definition: ConstraintSolver.hpp:196
void addSkeletons(const std::vector< dynamics::SkeletonPtr > &skeletons)
Add mutiple skeletons.
Definition: ConstraintSolver.cpp:107
void clearLastCollisionResult()
Clears the last collision result.
Definition: ConstraintSolver.cpp:192
void removeAllConstraints()
Remove all constraints.
Definition: ConstraintSolver.cpp:186
bool containConstraint(const ConstConstraintBasePtr &constraint) const
Check if the constraint is contained in this solver.
Definition: ConstraintSolver.cpp:364
virtual void solveConstrainedGroup(ConstrainedGroup &group)=0
std::vector< JointCoulombFrictionConstraintPtr > mJointCoulombFrictionConstraints
Joint Coulomb friction constraints those are automatically created.
Definition: ConstraintSolver.hpp:220
void removeConstraint(const ConstraintBasePtr &constraint)
Remove a constraint.
Definition: ConstraintSolver.cpp:169
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:255
void solveConstrainedGroups()
Solve constrained groups.
Definition: ConstraintSolver.cpp:618
std::vector< ContactConstraintPtr > mContactConstraints
Contact constraints those are automatically created.
Definition: ConstraintSolver.hpp:205
bool checkAndAddSkeleton(const dynamics::SkeletonPtr &skeleton)
Add skeleton if the constraint is not contained in this solver.
Definition: ConstraintSolver.cpp:348
void solve()
Solve constraint impulses and apply them to the skeletons.
Definition: ConstraintSolver.cpp:312
void addSkeleton(const dynamics::SkeletonPtr &skeleton)
Add single skeleton.
Definition: ConstraintSolver.cpp:87
collision::CollisionDetectorPtr mCollisionDetector
Collision detector.
Definition: ConstraintSolver.hpp:187
bool checkAndAddConstraint(const ConstraintBasePtr &constraint)
Add constraint if the constraint is not contained in this solver.
Definition: ConstraintSolver.cpp:372
void addConstraint(const ConstraintBasePtr &constraint)
Add a constraint.
Definition: ConstraintSolver.cpp:154
collision::CollisionDetectorPtr getCollisionDetector()
Get collision detector.
Definition: ConstraintSolver.cpp:242
double getTimeStep() const
Get time step.
Definition: ConstraintSolver.cpp:205
void setTimeStep(double _timeStep)
Set time step.
Definition: ConstraintSolver.cpp:198
collision::CollisionOption & getCollisionOption()
Returns collision option that is used for collision checkings in this ConstraintSolver to generate co...
Definition: ConstraintSolver.cpp:267
std::vector< MimicMotorConstraintPtr > mMimicMotorConstraints
Mimic motor constraints those are automatically created.
Definition: ConstraintSolver.hpp:217
std::vector< ServoMotorConstraintPtr > mServoMotorConstraints
Servo motor constraints those are automatically created.
Definition: ConstraintSolver.hpp:214
void removeSkeleton(const dynamics::SkeletonPtr &skeleton)
Remove single skeleton.
Definition: ConstraintSolver.cpp:120
std::vector< ConstrainedGroup > mConstrainedGroups
Constraint group list.
Definition: ConstraintSolver.hpp:229
collision::CollisionResult & getLastCollisionResult()
Return the last collision checking result.
Definition: ConstraintSolver.cpp:279
std::vector< ConstraintBasePtr > mManualConstraints
Constraints that manually added.
Definition: ConstraintSolver.hpp:223
const std::vector< dynamics::SkeletonPtr > & getSkeletons() const
Returns all the skeletons added to this ConstraintSolver.
Definition: ConstraintSolver.cpp:114
collision::CollisionGroupPtr mCollisionGroup
Collision group.
Definition: ConstraintSolver.hpp:190
std::vector< ConstraintBasePtr > mActiveConstraints
Active constraints.
Definition: ConstraintSolver.hpp:226
bool isSoftContact(const collision::Contact &contact) const
Return true if at least one of colliding body is soft body.
Definition: ConstraintSolver.cpp:625
double mTimeStep
Time step.
Definition: ConstraintSolver.hpp:199
void setLCPSolver(std::unique_ptr< LCPSolver > lcpSolver)
Set LCP solver.
Definition: ConstraintSolver.cpp:292
ConstraintSolver(double timeStep)
Constructor.
Definition: ConstraintSolver.cpp:61
void removeAllSkeletons()
Remove all skeletons in this constraint solver.
Definition: ConstraintSolver.cpp:147
virtual ~ConstraintSolver()
Destructor.
Definition: ConstraintSolver.cpp:81
std::vector< JointLimitConstraintPtr > mJointLimitConstraints
Joint limit constraints those are automatically created.
Definition: ConstraintSolver.hpp:211
void updateConstraints()
Update constraints.
Definition: ConstraintSolver.cpp:387
collision::CollisionOption mCollisionOption
Collision detection option.
Definition: ConstraintSolver.hpp:193
bool containSkeleton(const dynamics::ConstSkeletonPtr &skeleton) const
Check if the skeleton is contained in this solver.
Definition: ConstraintSolver.cpp:333
LCPSolver * getLCPSolver() const
Get LCP solver.
Definition: ConstraintSolver.cpp:301
void setCollisionDetector(collision::CollisionDetector *collisionDetector)
Set collision detector.
Definition: ConstraintSolver.cpp:211
void buildConstrainedGroups()
Build constrained groupsContact.
Definition: ConstraintSolver.cpp:562
Definition: LCPSolver.hpp:45
::fcl::CollisionResult CollisionResult
Definition: BackwardCompatibility.hpp:157
::fcl::Contact Contact
Definition: BackwardCompatibility.hpp:160
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:63
Definition: SharedLibraryManager.hpp:43