Skip to content

Commit cb77bf5

Browse files
committed
Revisit the near-rigid regime for implicit PD constraints
1 parent 806b9fa commit cb77bf5

File tree

3 files changed

+121
-29
lines changed

3 files changed

+121
-29
lines changed

multibody/contact_solvers/sap/sap_pd_controller_constraint.cc

Lines changed: 45 additions & 23 deletions
Original file line numberDiff line numberDiff line change
@@ -53,30 +53,52 @@ std::unique_ptr<AbstractValue> SapPdControllerConstraint<T>::DoMakeData(
5353
constexpr double beta = 0.1;
5454

5555
// Estimate regularization based on near-rigid regime threshold.
56-
// Rigid approximation constant: Rₙ = β²/(4π²)⋅wᵢ when the contact frequency
57-
// ωₙ is below the limit ωₙ⋅δt ≤ 2π. That is, the period is Tₙ = β⋅δt. See
58-
// [Castro et al., 2021] for details.
56+
// Rigid approximation constant: Rₙᵣ = β²/(4π²)⋅wᵢ when the contact frequency
57+
// ωₙᵣ is below the limit ωₙᵣ⋅δt ≤ 2π. That is, the near-rigid period is
58+
// Tₙᵣ = β⋅δt. See [Castro et al., 2021] for details.
5959
const double beta_factor = beta * beta / (4.0 * M_PI * M_PI);
60-
61-
// Effective gain values are clamped in the near-rigid regime.
62-
T Kp_eff = parameters_.Kp();
63-
T Kd_eff = parameters_.Kd();
64-
65-
// "Effective regularization" [Castro et al., 2021] for this constraint.
66-
const T R = 1.0 / (dt * (dt * Kp_eff + Kd_eff));
67-
68-
// "Near-rigid" regularization, [Castro et al., 2021].
69-
const T& w = delassus_estimation[0];
70-
const T R_near_rigid = beta_factor * w;
71-
72-
// In the near rigid regime we clamp Kp and Kd so that the effective
73-
// regularization is Rnr.
74-
if (R < R_near_rigid) {
75-
// Per [Castro et al., 2021], the relaxation time tau
76-
// for a critically damped constraint equals the time step, tau = dt.
77-
// With Kd = tau * Kp, and R = Rₙᵣ, we obtain Rₙᵣ⁻¹ = 2δt² Kₚ.
78-
Kp_eff = 1.0 / R_near_rigid / (2.0 * dt * dt);
79-
Kd_eff = dt * Kp_eff;
60+
const T R_nr = beta_factor * delassus_estimation[0];
61+
62+
// "Effective regularization" [Castro et al., 2021] for this constraint based
63+
// on user specified gains.
64+
const T& Kp = parameters_.Kp();
65+
const T& Kd = parameters_.Kd();
66+
const T R = 1.0 / (dt * (dt * Kp + Kd));
67+
68+
// R determines numerical conditioning for this constraint. The SAP problem
69+
// can become ill-conditioned for small enough values of R. To keep
70+
// conditioning under control, [Castro et al., 2021] propose to use Rₙᵣ as a
71+
// lower bound such that the time scales introduced by this constraint in the
72+
// overall dynamics are of order Tₙᵣ = β⋅δt (i.e. under resolved for β < 1).
73+
//
74+
// However, we also want to respect the ratio Kd/Kp set by the user. In
75+
// particular, if Kp = 0, that means the user wants velocity control only.
76+
// Similarly, if Kd = 0, the user wants position control only. From the
77+
// expression above for R, we observe we can write the effective
78+
// regularization R in two different but equivalent ways:
79+
// 1) R = 1/(δt⋅(δt + Kd/Kp )⋅Kp), if Kp > 0
80+
// 2) R = 1/(δt⋅( 1 + δt⋅Kp/Kd)⋅Kd), if Kd > 0
81+
// Keeping the ratio Kd/Kp (or its inverse) constant, and equating R = Rₙᵣ,
82+
// we can obtain expressions for the near-rigid regime gains from:
83+
// 1) Rₙᵣ = 1/(δt⋅(δt + Kd/Kp )⋅Kpₙᵣ), if Kp > 0
84+
// 2) Rₙᵣ = 1/(δt⋅( 1 + δt⋅Kp/Kd)⋅Kdₙᵣ), if Kd > 0
85+
// From thse we can obtain the desired gains in terms of Rₙᵣ as:
86+
// 1) δt⋅Kpₙᵣ = 1 / ( (δt + Kd/Kp )⋅Rₙᵣ) > 1/(2⋅δt⋅Rₙᵣ), if δt⋅Kp > Kd
87+
// 2) Kdₙᵣ = 1/(δt⋅( 1 + δt⋅Kp/Kd)⋅Rₙᵣ) > 1/(2⋅δt⋅Rₙᵣ), if δt⋅Kp < Kd
88+
// We therefore use δt⋅Kp < Kd as the criterion to use expression (1),
89+
// keeping Kd/Kp constant, or (2), keeping Kp/Kd constant.
90+
T Kp_eff = Kp;
91+
T Kd_eff = Kd;
92+
if (R < R_nr) {
93+
if (dt * Kp > Kd) {
94+
const T tau = Kd / Kp;
95+
Kp_eff = 1.0 / (dt * (dt + tau) * R_nr);
96+
Kd_eff = tau * Kp_eff; // We keep ratio tau constant.
97+
} else {
98+
const T tau_inv = Kp / Kd;
99+
Kd_eff = 1.0 / (dt * (1.0 + dt * tau_inv) * R_nr);
100+
Kp_eff = tau_inv * Kd_eff; // We keep ratio tau_inv constant.
101+
}
80102
}
81103

82104
// Make data.

multibody/contact_solvers/sap/sap_pd_controller_constraint.h

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -104,9 +104,12 @@ class SapPdControllerConstraint final : public SapConstraint<T> {
104104

105105
// TODO(amcastro-tri): Consider extending support for both gains being zero.
106106
/* Constructs a valid set of parameters.
107-
@param Kp Proportional gain. It must be strictly positive.
107+
@param Kp Proportional gain. It must be non-negative.
108108
@param Kd Derivative gain. It must be non-negative.
109109
@param effort_limit Effort limit. It must be strictly positive.
110+
111+
@pre At least one of Kp and Kd must be strictly positive. That is, they
112+
cannot both be zero.
110113
@note Units will depend on the joint type on which this constraint is
111114
added. E.g. For a prismatic joint, Kp will be in N/m, Kd in N⋅s/m, and
112115
effort_limit in N. */

multibody/contact_solvers/sap/test/sap_pd_controller_constraint_test.cc

Lines changed: 72 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -183,7 +183,8 @@ GTEST_TEST(SapPdControllerConstraint, MakeDataNearRigidRegime) {
183183

184184
const double dt = 0.015;
185185
const double large_Kp = 1e8;
186-
const double large_Kd = 1e7;
186+
const double tau = 0.13;
187+
const double large_Kd = tau * large_Kp;
187188
const double effort_limit = 0.3;
188189
const Parameters p{large_Kp, large_Kd, effort_limit};
189190
// The configuration is irrelevant for this test.
@@ -193,19 +194,85 @@ GTEST_TEST(SapPdControllerConstraint, MakeDataNearRigidRegime) {
193194
const VectorXd w = Vector1d::Constant(1.6);
194195

195196
const double Rnr = kBeta * kBeta / (4.0 * M_PI * M_PI) * w(0);
196-
// Expected near-rigid parameters.
197-
const double Kp_nr = 1.0 / Rnr / (2.0 * dt * dt);
198-
const double Kd_nr = dt * Kp_nr;
197+
// Expected near-rigid parameters. Time scale tau is kept constant.
198+
const double Kp_nr = 1.0 / Rnr / (dt * (dt + tau));
199+
const double Kd_nr = tau * Kp_nr;
199200

200201
// Verify that gains were clamped to be in the near-rigid regime.
201202
auto abstract_data = c.MakeData(dt, w);
202203
const auto& data =
203204
abstract_data->get_value<SapPdControllerConstraintData<double>>();
204-
EXPECT_NEAR(data.Kp_eff(), Kp_nr, kEps);
205+
EXPECT_NEAR(data.Kp_eff(), Kp_nr, kEps * large_Kp);
206+
EXPECT_NEAR(data.Kd_eff(), Kd_nr, kEps * large_Kd);
207+
EXPECT_EQ(data.time_step(), dt); // not affected.
208+
}
209+
210+
// Verify the effective gains within the near-rigid regime when the user sets
211+
// the position gain Kp to zero. In particular, the effective position gain
212+
// should remain zero to respect the user's desire to do velocity control only.
213+
GTEST_TEST(SapPdControllerConstraint, MakeDataNearRigidRegimeWithZeroKp) {
214+
// This value of near-rigid parameter is the one internally used by
215+
// SapPdControllerConstraint and they must remain in sync.
216+
constexpr double kBeta = 0.1;
217+
218+
const double dt = 0.015;
219+
const double Kp = 0.0;
220+
const double large_Kd = 1.0e8;
221+
const double effort_limit = 0.3;
222+
const Parameters p{Kp, large_Kd, effort_limit};
223+
// The configuration is irrelevant for this test.
224+
const Configuration k = MakeArbitraryConfiguration();
225+
const SapPdControllerConstraint<double> c(k, p);
226+
// Arbitrary value for the Delassus operator.
227+
const VectorXd w = Vector1d::Constant(1.6);
228+
229+
const double Rnr = kBeta * kBeta / (4.0 * M_PI * M_PI) * w(0);
230+
// Expected near-rigid parameters. The user wants velocity control, and we
231+
// should respect that.
232+
const double Kd_nr = 1.0 / (dt * Rnr);
233+
234+
// Verify that gains were clamped to be in the near-rigid regime.
235+
auto abstract_data = c.MakeData(dt, w);
236+
const auto& data =
237+
abstract_data->get_value<SapPdControllerConstraintData<double>>();
238+
EXPECT_EQ(data.Kp_eff(), 0.0);
205239
EXPECT_NEAR(data.Kd_eff(), Kd_nr, kEps);
206240
EXPECT_EQ(data.time_step(), dt); // not affected.
207241
}
208242

243+
// Verify the effective gains within the near-rigid regime when the user sets
244+
// the derivative gain Kd to zero. In particular, the effective derivate gain
245+
// should remain zero to respect the user's desire to do position control only.
246+
GTEST_TEST(SapPdControllerConstraint, MakeDataNearRigidRegimeWithZeroKd) {
247+
// This value of near-rigid parameter is the one internally used by
248+
// SapPdControllerConstraint and they must remain in sync.
249+
constexpr double kBeta = 0.1;
250+
251+
const double dt = 0.015;
252+
const double large_Kp = 1e8;
253+
const double Kd = 0.0;
254+
const double effort_limit = 0.3;
255+
const Parameters p{large_Kp, Kd, effort_limit};
256+
// The configuration is irrelevant for this test.
257+
const Configuration k = MakeArbitraryConfiguration();
258+
const SapPdControllerConstraint<double> c(k, p);
259+
// Arbitrary value for the Delassus operator.
260+
const VectorXd w = Vector1d::Constant(1.6);
261+
262+
const double Rnr = kBeta * kBeta / (4.0 * M_PI * M_PI) * w(0);
263+
// Expected near-rigid parameters. The user wants position control, and we
264+
// should respect that.
265+
const double Kp_nr = 1.0 / (dt * dt * Rnr);
266+
267+
// Verify that gains were clamped to be in the near-rigid regime.
268+
auto abstract_data = c.MakeData(dt, w);
269+
const auto& data =
270+
abstract_data->get_value<SapPdControllerConstraintData<double>>();
271+
EXPECT_NEAR(data.Kp_eff(), Kp_nr, kEps);
272+
EXPECT_EQ(data.Kd_eff(), 0.0);
273+
EXPECT_EQ(data.time_step(), dt); // not affected.
274+
}
275+
209276
// This method validates analytical gradients implemented by
210277
// SapPdControllerConstraint using automatic differentiation.
211278
void ValidateGradients(double v) {

0 commit comments

Comments
 (0)