/
JointConstraint.cpp
189 lines (165 loc) · 6.04 KB
/
JointConstraint.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
/*
* Copyright (c) 2014-2015, Georgia Tech Research Corporation
* All rights reserved.
*
* Author(s): Jeongseok Lee <jslee02@gmail.com>
*
* Georgia Tech Graphics Lab and Humanoid Robotics Lab
*
* Directed by Prof. C. Karen Liu and Prof. Mike Stilman
* <karenliu@cc.gatech.edu> <mstilman@cc.gatech.edu>
*
* This file is provided under the following "BSD-style" License:
* Redistribution and use in source and binary forms, with or
* without modification, are permitted provided that the following
* conditions are met:
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
* CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
* INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
* CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
* SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF
* USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/
#include "dart/constraint/JointConstraint.h"
#include <cassert>
#include <iostream>
#include "dart/common/Console.h"
#define DART_ERROR_ALLOWANCE 0.0
#define DART_ERP 0.01
#define DART_MAX_ERV 1e+1
#define DART_CFM 1e-9
namespace dart {
namespace constraint {
double JointConstraint::mErrorAllowance = DART_ERROR_ALLOWANCE;
double JointConstraint::mErrorReductionParameter = DART_ERP;
double JointConstraint::mMaxErrorReductionVelocity = DART_MAX_ERV;
double JointConstraint::mConstraintForceMixing = DART_CFM;
//==============================================================================
JointConstraint::JointConstraint(dynamics::BodyNode* _body)
: ConstraintBase(),
mBodyNode1(_body),
mBodyNode2(nullptr)
{
assert(_body);
}
//==============================================================================
JointConstraint::JointConstraint(dynamics::BodyNode* _body1,
dynamics::BodyNode* _body2)
: ConstraintBase(),
mBodyNode1(_body1),
mBodyNode2(_body2)
{
assert(_body1);
assert(_body2);
}
//==============================================================================
JointConstraint::~JointConstraint()
{
}
//==============================================================================
void JointConstraint::setErrorAllowance(double _allowance)
{
// Clamp error reduction parameter if it is out of the range
if (_allowance < 0.0)
{
dtwarn << "Error reduction parameter[" << _allowance
<< "] is lower than 0.0. "
<< "It is set to 0.0." << std::endl;
mErrorAllowance = 0.0;
}
mErrorAllowance = _allowance;
}
//==============================================================================
double JointConstraint::getErrorAllowance()
{
return mErrorAllowance;
}
//==============================================================================
void JointConstraint::setErrorReductionParameter(double _erp)
{
// Clamp error reduction parameter if it is out of the range [0, 1]
if (_erp < 0.0)
{
dtwarn << "Error reduction parameter[" << _erp << "] is lower than 0.0. "
<< "It is set to 0.0." << std::endl;
mErrorReductionParameter = 0.0;
}
if (_erp > 1.0)
{
dtwarn << "Error reduction parameter[" << _erp << "] is greater than 1.0. "
<< "It is set to 1.0." << std::endl;
mErrorReductionParameter = 1.0;
}
mErrorReductionParameter = _erp;
}
//==============================================================================
double JointConstraint::getErrorReductionParameter()
{
return mErrorReductionParameter;
}
//==============================================================================
void JointConstraint::setMaxErrorReductionVelocity(double _erv)
{
// Clamp maximum error reduction velocity if it is out of the range
if (_erv < 0.0)
{
dtwarn << "Maximum error reduction velocity[" << _erv
<< "] is lower than 0.0. "
<< "It is set to 0.0." << std::endl;
mMaxErrorReductionVelocity = 0.0;
}
mMaxErrorReductionVelocity = _erv;
}
//==============================================================================
double JointConstraint::getMaxErrorReductionVelocity()
{
return mMaxErrorReductionVelocity;
}
//==============================================================================
void JointConstraint::setConstraintForceMixing(double _cfm)
{
// Clamp constraint force mixing parameter if it is out of the range
if (_cfm < 1e-9)
{
dtwarn << "Constraint force mixing parameter[" << _cfm
<< "] is lower than 1e-9. " << "It is set to 1e-9." << std::endl;
mConstraintForceMixing = 1e-9;
}
if (_cfm > 1.0)
{
dtwarn << "Constraint force mixing parameter[" << _cfm
<< "] is greater than 1.0. " << "It is set to 1.0." << std::endl;
mConstraintForceMixing = 1.0;
}
mConstraintForceMixing = _cfm;
}
//==============================================================================
double JointConstraint::getConstraintForceMixing()
{
return mConstraintForceMixing;
}
//==============================================================================
dynamics::BodyNode* JointConstraint::getBodyNode1() const
{
return mBodyNode1;
}
//==============================================================================
dynamics::BodyNode* JointConstraint::getBodyNode2() const
{
return mBodyNode2;
}
} // namespace constraint
} // namespace dart