DART 6.13.2
Loading...
Searching...
No Matches
ConstraintSolver.hpp
Go to the documentation of this file.
1/*
2 * Copyright (c) 2011-2022, 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
45
46namespace dart {
47
48namespace dynamics {
49class Skeleton;
50class ShapeNodeCollisionObject;
51} // namespace dynamics
52
53namespace constraint {
54
57{
58public:
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
108
111 std::size_t getNumConstraints() const;
112
115
118
122 DART_DEPRECATED(6.13)
123 std::vector<constraint::ConstraintBasePtr> getConstraints();
124
128 DART_DEPRECATED(6.13)
129 std::vector<constraint::ConstConstraintBasePtr> getConstraints() const;
130
140 template <typename Func>
141 void eachConstraint(Func func) const;
142
152 template <typename Func>
153 void eachConstraint(Func func);
154
157
159 virtual void setTimeStep(double _timeStep);
160
162 double getTimeStep() const;
163
167 DART_DEPRECATED(6.0)
168 void setCollisionDetector(collision::CollisionDetector* collisionDetector);
169
172 const std::shared_ptr<collision::CollisionDetector>& collisionDetector);
173
175 collision::CollisionDetectorPtr getCollisionDetector();
176
178 collision::ConstCollisionDetectorPtr getCollisionDetector() const;
179
182 collision::CollisionGroupPtr getCollisionGroup();
183
186 collision::ConstCollisionGroupPtr getCollisionGroup() const;
187
190 collision::CollisionOption& getCollisionOption();
191
194 const collision::CollisionOption& getCollisionOption() const;
195
197 collision::CollisionResult& getLastCollisionResult();
198
200 const collision::CollisionResult& getLastCollisionResult() const;
201
203 DART_DEPRECATED(6.7)
204 void setLCPSolver(std::unique_ptr<LCPSolver> lcpSolver);
205
207 DART_DEPRECATED(6.7)
208 LCPSolver* getLCPSolver() const;
209
211 void solve();
212
215 virtual void setFromOtherConstraintSolver(const ConstraintSolver& other);
216
220
225
234
235protected:
236 // TODO(JS): Docstring
237 virtual void solveConstrainedGroup(ConstrainedGroup& group) = 0;
238
242 DART_DEPRECATED(6.13)
243 bool containSkeleton(const dynamics::ConstSkeletonPtr& skeleton) const;
244
246 bool hasSkeleton(const dynamics::ConstSkeletonPtr& skeleton) const;
247
249 bool checkAndAddSkeleton(const dynamics::SkeletonPtr& skeleton);
250
252 bool containConstraint(const ConstConstraintBasePtr& constraint) const;
253
255 bool checkAndAddConstraint(const ConstraintBasePtr& constraint);
256
258 void updateConstraints();
259
262
265
267 bool isSoftContact(const collision::Contact& contact) const;
268
270
272 collision::CollisionDetectorPtr mCollisionDetector;
273
275 collision::CollisionGroupPtr mCollisionGroup;
276
278 collision::CollisionOption mCollisionOption;
279
281 collision::CollisionResult mCollisionResult;
282
284 double mTimeStep;
285
287 std::vector<dynamics::SkeletonPtr> mSkeletons;
288
291
294
297
300
304
307
310
313
316};
317
318} // namespace constraint
319} // namespace dart
320
321#include "dart/constraint/detail/ConstraintSolver-impl.hpp"
322
323#endif // DART_CONSTRAINT_CONSTRAINTSOVER_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