DART 6.13.2
Loading...
Searching...
No Matches
ContactConstraint.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_CONTACTCONSTRAINT_HPP_
34#define DART_CONSTRAINT_CONTACTCONSTRAINT_HPP_
35
40
41namespace dart {
42
43namespace dynamics {
44class BodyNode;
45class Skeleton;
46} // namespace dynamics
47
48namespace constraint {
49
52{
53public:
56 collision::Contact& contact,
57 double timeStep,
58 const ContactSurfaceParams& contactSurfaceParams);
59
61 DART_DEPRECATED(6.13)
62 ContactConstraint(collision::Contact& contact, double timeStep);
63
65 ~ContactConstraint() override = default;
66
67 // Documentation inherited
68 const std::string& getType() const override;
69
71 static const std::string& getStaticType();
72
73 //----------------------------------------------------------------------------
74 // Property settings
75 //----------------------------------------------------------------------------
76
78 static void setErrorAllowance(double allowance);
79
81 static double getErrorAllowance();
82
84 static void setErrorReductionParameter(double erp);
85
87 static double getErrorReductionParameter();
88
90 static void setMaxErrorReductionVelocity(double erv);
91
93 static double getMaxErrorReductionVelocity();
94
96 static void setConstraintForceMixing(double cfm);
97
99 static double getConstraintForceMixing();
100
102 void setFrictionDirection(const Eigen::Vector3d& dir);
103
105 const Eigen::Vector3d& getFrictionDirection1() const;
106
107 //----------------------------------------------------------------------------
108 // Friendship
109 //----------------------------------------------------------------------------
110
111 friend class ConstraintSolver;
112 friend class ConstrainedGroup;
114
115protected:
116 //----------------------------------------------------------------------------
117 // Constraint virtual functions
118 //----------------------------------------------------------------------------
119
120 // Documentation inherited
121 void update() override;
122
123 // Documentation inherited
124 void getInformation(ConstraintInfo* info) override;
125
126 // Documentation inherited
127 void applyUnitImpulse(std::size_t index) override;
128
129 // Documentation inherited
130 void getVelocityChange(double* vel, bool withCfm) override;
131
132 // Documentation inherited
133 void excite() override;
134
135 // Documentation inherited
136 void unexcite() override;
137
138 // Documentation inherited
139 void applyImpulse(double* lambda) override;
140
141 // Documentation inherited
142 dynamics::SkeletonPtr getRootSkeleton() const override;
143
144 // Documentation inherited
145 void uniteSkeletons() override;
146
147 // Documentation inherited
148 bool isActive() const override;
149
150 DART_DEPRECATED(6.13)
151 static double computeFrictionCoefficient(
152 const dynamics::ShapeNode* shapeNode);
153 DART_DEPRECATED(6.13)
155 const dynamics::ShapeNode* shapeNode);
156 DART_DEPRECATED(6.13)
158 const dynamics::ShapeNode* shapeNode);
159 DART_DEPRECATED(6.13)
160 static double computePrimarySlipCompliance(
161 const dynamics::ShapeNode* shapeNode);
162 DART_DEPRECATED(6.13)
163 static double computeSecondarySlipCompliance(
164 const dynamics::ShapeNode* shapeNode);
165 DART_DEPRECATED(6.13)
166 static Eigen::Vector3d computeWorldFirstFrictionDir(
167 const dynamics::ShapeNode* shapenode);
168 DART_DEPRECATED(6.13)
169 static double computeRestitutionCoefficient(
170 const dynamics::ShapeNode* shapeNode);
171
172private:
173 using TangentBasisMatrix = Eigen::Matrix<double, 3, 2>;
174
178 void getRelVelocity(double* relVel);
179
182
185
186 // The following functions for getting and setting slip compliance and
187 // accessing the contact object are meant to be used by ConstraintSolver to
188 // update the slip compliances based on the number of contacts between the
189 // collision objects.
190 //
192 double getPrimarySlipCompliance() const;
193
195 void setPrimarySlipCompliance(double slip);
196
198 double getSecondarySlipCompliance() const;
199
201 void setSecondarySlipCompliance(double slip);
202
204 const collision::Contact& getContact() const;
205
206private:
208 double mTimeStep;
209
212
215
217 collision::Contact& mContact;
218
221
224
227
230
233
236
242
245
247 Eigen::Matrix<double, 6, Eigen::Dynamic> mSpatialNormalA;
248
250 Eigen::Matrix<double, 6, Eigen::Dynamic> mSpatialNormalB;
251
254
257
260
263
265 static double mErrorAllowance;
266
270
273
278};
279// TODO(JS): Create SelfContactConstraint.
280
281} // namespace constraint
282} // namespace dart
283
284#endif // DART_CONSTRAINT_CONTACTCONSTRAINT_HPP_
#define DART_DEPRECATED(version)
Definition Deprecated.hpp:51
std::size_t index
Definition SkelParser.cpp:1673
ConstrainedGroup is a group of skeletons that interact each other with constraints.
Definition ConstrainedGroup.hpp:59
Constraint is a base class of concrete constraints classes.
Definition ConstraintBase.hpp:75
ConstraintSolver manages constraints and computes constraint impulses.
Definition ConstraintSolver.hpp:57
ContactConstraint represents a contact constraint between two bodies.
Definition ContactConstraint.hpp:52
static const std::string & getStaticType()
Returns constraint type for this class.
Definition ContactConstraint.cpp:246
double mTimeStep
Time step.
Definition ContactConstraint.hpp:208
const Eigen::Vector3d & getFrictionDirection1() const
Get first frictional direction.
Definition ContactConstraint.cpp:348
void setFrictionDirection(const Eigen::Vector3d &dir)
Set first frictional direction.
Definition ContactConstraint.cpp:342
Eigen::Vector3d mContactSurfaceMotionVelocity
Velocity of the contact independent of friction x = vel.
Definition ContactConstraint.hpp:241
bool mIsFrictionOn
Definition ContactConstraint.hpp:253
void update() override
Update constraint using updated Skeleton's states.
Definition ContactConstraint.cpp:354
static void setErrorAllowance(double allowance)
Set global error reduction parameter.
Definition ContactConstraint.cpp:253
void excite() override
Excite the constraint.
Definition ContactConstraint.cpp:601
static double mMaxErrorReductionVelocity
Maximum error reduction velocity.
Definition ContactConstraint.hpp:272
double getPrimarySlipCompliance() const
Get primary slip compliance.
Definition ContactConstraint.cpp:861
bool mActive
Definition ContactConstraint.hpp:262
bool isActive() const override
Return true if this constraint is active.
Definition ContactConstraint.cpp:689
static void setErrorReductionParameter(double erp)
Set global error reduction parameter.
Definition ContactConstraint.cpp:274
void applyImpulse(double *lambda) override
Apply computed constraint impulse to constrained skeletons.
Definition ContactConstraint.cpp:621
double mPrimarySlipCompliance
Primary Coefficient of Slip Compliance.
Definition ContactConstraint.hpp:229
static void setMaxErrorReductionVelocity(double erv)
Set global error reduction parameter.
Definition ContactConstraint.cpp:300
static double getConstraintForceMixing()
Get global constraint force mixing parameter.
Definition ContactConstraint.cpp:336
static double computeRestitutionCoefficient(const dynamics::ShapeNode *shapeNode)
Definition ContactConstraint.cpp:740
static double computePrimarySlipCompliance(const dynamics::ShapeNode *shapeNode)
Definition ContactConstraint.cpp:718
Eigen::Matrix< double, 6, Eigen::Dynamic > mSpatialNormalB
Local body jacobians for mBodyNode2.
Definition ContactConstraint.hpp:250
const collision::Contact & getContact() const
Get contact object associated witht this constraint.
Definition ContactConstraint.cpp:885
double mSecondarySlipCompliance
Secondary Coefficient of Slip Compliance.
Definition ContactConstraint.hpp:232
void updateFirstFrictionalDirection()
Definition ContactConstraint.cpp:758
void setPrimarySlipCompliance(double slip)
Set primary slip compliance.
Definition ContactConstraint.cpp:867
void getInformation(ConstraintInfo *info) override
Fill LCP variables.
Definition ContactConstraint.cpp:363
static double computeSecondarySlipCompliance(const dynamics::ShapeNode *shapeNode)
Definition ContactConstraint.cpp:725
static double mErrorReductionParameter
Global constraint error redection parameter in the range of [0, 1].
Definition ContactConstraint.hpp:269
static double getErrorAllowance()
Get global error reduction parameter.
Definition ContactConstraint.cpp:268
static double computeFrictionCoefficient(const dynamics::ShapeNode *shapeNode)
Definition ContactConstraint.cpp:695
static double computeSecondaryFrictionCoefficient(const dynamics::ShapeNode *shapeNode)
Definition ContactConstraint.cpp:710
collision::Contact & mContact
Contact between mBodyNode1 and mBodyNode2.
Definition ContactConstraint.hpp:217
void getRelVelocity(double *relVel)
Get change in relative velocity at contact point due to external impulse.
Definition ContactConstraint.cpp:678
double mPrimaryFrictionCoeff
Primary Coefficient of Friction.
Definition ContactConstraint.hpp:223
TangentBasisMatrix getTangentBasisMatrixODE(const Eigen::Vector3d &n)
Definition ContactConstraint.cpp:772
const std::string & getType() const override
Returns a string representing the constraint type.
Definition ContactConstraint.cpp:240
static double getMaxErrorReductionVelocity()
Get global error reduction parameter.
Definition ContactConstraint.cpp:315
std::size_t mAppliedImpulseIndex
Index of applied impulse.
Definition ContactConstraint.hpp:256
dynamics::BodyNode * mBodyNodeA
Fircst body node.
Definition ContactConstraint.hpp:211
void applyUnitImpulse(std::size_t index) override
Apply unit impulse to constraint space.
Definition ContactConstraint.cpp:497
void unexcite() override
Unexcite the constraint.
Definition ContactConstraint.cpp:611
~ContactConstraint() override=default
Destructor.
void getVelocityChange(double *vel, bool withCfm) override
Get velocity change due to the uint impulse.
Definition ContactConstraint.cpp:567
static double getErrorReductionParameter()
Get global error reduction parameter.
Definition ContactConstraint.cpp:294
static double computePrimaryFrictionCoefficient(const dynamics::ShapeNode *shapeNode)
Definition ContactConstraint.cpp:702
static double mErrorAllowance
Global constraint error allowance.
Definition ContactConstraint.hpp:265
double getSecondarySlipCompliance() const
Get secondary slip compliance.
Definition ContactConstraint.cpp:873
bool mIsBounceOn
Definition ContactConstraint.hpp:259
Eigen::Matrix< double, 6, Eigen::Dynamic > mSpatialNormalA
Local body jacobians for mBodyNode1.
Definition ContactConstraint.hpp:247
double mRestitutionCoeff
Coefficient of restitution.
Definition ContactConstraint.hpp:235
void uniteSkeletons() override
Definition ContactConstraint.cpp:830
static Eigen::Vector3d computeWorldFirstFrictionDir(const dynamics::ShapeNode *shapenode)
Definition ContactConstraint.cpp:733
Eigen::Matrix< double, 3, 2 > TangentBasisMatrix
Definition ContactConstraint.hpp:173
static double mConstraintForceMixing
Global constraint force mixing parameter in the range of [1e-9, 1].
Definition ContactConstraint.hpp:277
dynamics::BodyNode * mBodyNodeB
Second body node.
Definition ContactConstraint.hpp:214
dynamics::SkeletonPtr getRootSkeleton() const override
Definition ContactConstraint.cpp:747
bool mIsSelfCollision
Whether this contact is self-collision.
Definition ContactConstraint.hpp:244
double mSecondaryFrictionCoeff
Secondary Coefficient of Friction.
Definition ContactConstraint.hpp:226
Eigen::Vector3d mFirstFrictionalDirection
First frictional direction.
Definition ContactConstraint.hpp:220
static void setConstraintForceMixing(double cfm)
Set global constraint force mixing parameter.
Definition ContactConstraint.cpp:321
void setSecondarySlipCompliance(double slip)
Set secondary slip compliance.
Definition ContactConstraint.cpp:879
Default contact surface handler.
Definition ContactSurface.hpp:152
BodyNode class represents a single node of the skeleton.
Definition BodyNode.hpp:80
Definition ShapeNode.hpp:49
Definition Random-impl.hpp:92
std::shared_ptr< Skeleton > SkeletonPtr
Definition SmartPointer.hpp:60
Definition BulletCollisionDetector.cpp:60
Contact information.
Definition Contact.hpp:46
ConstraintInfo.
Definition ConstraintBase.hpp:50
Computed parameters of the contact surface.
Definition ContactSurface.hpp:62