dart
ConstraintSolver.hpp
1 /*
2  * Copyright (c) 2011-2021, 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 
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"
45 
46 namespace dart {
47 
48 namespace dynamics {
49 class Skeleton;
50 class ShapeNodeCollisionObject;
51 } // namespace dynamics
52 
53 namespace dynamics {
54 
57 {
58 public:
64  DART_DEPRECATED(6.8)
65  explicit ConstraintSolver(double timeStep);
66 
67  // TODO(JS): Remove timeStep. The timestep can be set by world when a
68  // constraint solver is assigned to a world.
69  // Deprecate
70 
73 
75  // TODO: implement copy constructor since this class contains a pointer to
76  // allocated memory.
77  ConstraintSolver(const ConstraintSolver& other) = delete;
78 
80  virtual ~ConstraintSolver() = default;
81 
83  void addSkeleton(const dynamics::SkeletonPtr& skeleton);
84 
86  void addSkeletons(const std::vector<dynamics::SkeletonPtr>& skeletons);
87 
89  const std::vector<dynamics::SkeletonPtr>& getSkeletons() const;
90 
92  void removeSkeleton(const dynamics::SkeletonPtr& skeleton);
93 
95  void removeSkeletons(const std::vector<dynamics::SkeletonPtr>& skeletons);
96 
98  void removeAllSkeletons();
99 
101  void addConstraint(const ConstraintBasePtr& constraint);
102 
104  void removeConstraint(const ConstraintBasePtr& constraint);
105 
107  void removeAllConstraints();
108 
111  std::size_t getNumConstraints() const;
112 
114  dynamics::ConstraintBasePtr getConstraint(std::size_t index);
115 
117  dynamics::ConstConstraintBasePtr getConstraint(std::size_t index) const;
118 
120  std::vector<dynamics::ConstraintBasePtr> getConstraints();
121 
123  std::vector<dynamics::ConstConstraintBasePtr> getConstraints() const;
124 
126  void clearLastCollisionResult();
127 
129  virtual void setTimeStep(double _timeStep);
130 
132  double getTimeStep() const;
133 
137  DART_DEPRECATED(6.0)
138  void setCollisionDetector(collision::CollisionDetector* collisionDetector);
139 
141  void setCollisionDetector(
142  const std::shared_ptr<collision::CollisionDetector>& collisionDetector);
143 
145  collision::CollisionDetectorPtr getCollisionDetector();
146 
148  collision::ConstCollisionDetectorPtr getCollisionDetector() const;
149 
152  collision::CollisionGroupPtr getCollisionGroup();
153 
156  collision::ConstCollisionGroupPtr getCollisionGroup() const;
157 
160  collision::CollisionOption& getCollisionOption();
161 
164  const collision::CollisionOption& getCollisionOption() const;
165 
167  collision::CollisionResult& getLastCollisionResult();
168 
170  const collision::CollisionResult& getLastCollisionResult() const;
171 
173  DART_DEPRECATED(6.7)
174  void setLCPSolver(std::unique_ptr<LCPSolver> lcpSolver);
175 
177  DART_DEPRECATED(6.7)
178  LCPSolver* getLCPSolver() const;
179 
181  void solve();
182 
185  virtual void setFromOtherConstraintSolver(const ConstraintSolver& other);
186 
187 protected:
188  // TODO(JS): Docstring
189  virtual void solveConstrainedGroup(ConstrainedGroup& group) = 0;
190 
192  bool containSkeleton(const dynamics::ConstSkeletonPtr& skeleton) const;
193 
195  bool checkAndAddSkeleton(const dynamics::SkeletonPtr& skeleton);
196 
198  bool containConstraint(const ConstConstraintBasePtr& constraint) const;
199 
201  bool checkAndAddConstraint(const ConstraintBasePtr& constraint);
202 
204  void updateConstraints();
205 
207  void buildConstrainedGroups();
208 
210  void solveConstrainedGroups();
211 
213  bool isSoftContact(const collision::Contact& contact) const;
214 
216 
218  collision::CollisionDetectorPtr mCollisionDetector;
219 
221  collision::CollisionGroupPtr mCollisionGroup;
222 
225 
228 
230  double mTimeStep;
231 
233  std::vector<dynamics::SkeletonPtr> mSkeletons;
234 
236  std::vector<ContactConstraintPtr> mContactConstraints;
237 
239  std::vector<SoftContactConstraintPtr> mSoftContactConstraints;
240 
242  std::vector<JointLimitConstraintPtr> mJointLimitConstraints;
243 
245  std::vector<ServoMotorConstraintPtr> mServoMotorConstraints;
246 
248  std::vector<MimicMotorConstraintPtr> mMimicMotorConstraints;
249 
251  std::vector<JointCoulombFrictionConstraintPtr>
253 
255  std::vector<ConstraintBasePtr> mManualConstraints;
256 
258  std::vector<ConstraintBasePtr> mActiveConstraints;
259 
261  std::vector<ConstrainedGroup> mConstrainedGroups;
262 };
263 
264 } // namespace dynamics
265 } // namespace dart
266 
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
Contact information.
Definition: Contact.hpp:44
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