-
Notifications
You must be signed in to change notification settings - Fork 1.2k
/
inverse_kinematics_test.cc
419 lines (364 loc) · 17.6 KB
/
inverse_kinematics_test.cc
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
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
#include "drake/multibody/inverse_kinematics/inverse_kinematics.h"
#include <gtest/gtest.h>
#include "drake/common/find_resource.h"
#include "drake/common/test_utilities/eigen_matrix_compare.h"
#include "drake/math/rotation_matrix.h"
#include "drake/math/wrap_to.h"
#include "drake/multibody/inverse_kinematics/test/inverse_kinematics_test_utilities.h"
#include "drake/solvers/create_constraint.h"
#include "drake/solvers/solve.h"
// TODO(eric.cousineau): Replace manual coordinate indexing with more semantic
// operations (`CalcRelativeTransform`, `SetFreeBodyPose`).
namespace drake {
namespace multibody {
Eigen::Quaterniond Vector4ToQuaternion(
const Eigen::Ref<const Eigen::Vector4d>& q) {
return Eigen::Quaterniond(q(0), q(1), q(2), q(3));
}
class TwoFreeBodiesTest : public ::testing::Test {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(TwoFreeBodiesTest)
TwoFreeBodiesTest()
: two_bodies_plant_(ConstructTwoFreeBodiesPlant<double>()),
// TODO(hongkai.dai) call GetFrameByName()
body1_frame_(two_bodies_plant_->GetFrameByName("body1")),
body2_frame_(two_bodies_plant_->GetFrameByName("body2")),
ik_(*two_bodies_plant_) {}
~TwoFreeBodiesTest() override {}
std::unique_ptr<systems::Context<double>> RetrieveSolution(
const solvers::MathematicalProgramResult& result) {
const auto q_sol = result.GetSolution(ik_.q());
body1_quaternion_sol_ = Vector4ToQuaternion(q_sol.head<4>());
body1_position_sol_ = q_sol.segment<3>(4);
body2_quaternion_sol_ = Vector4ToQuaternion(q_sol.segment<4>(7));
body2_position_sol_ = q_sol.tail<3>();
auto context = two_bodies_plant_->CreateDefaultContext();
two_bodies_plant_->SetPositions(context.get(), q_sol);
return context;
}
protected:
std::unique_ptr<MultibodyPlant<double>> two_bodies_plant_;
const Frame<double>& body1_frame_;
const Frame<double>& body2_frame_;
InverseKinematics ik_;
Eigen::Quaterniond body1_quaternion_sol_;
Eigen::Quaterniond body2_quaternion_sol_;
Eigen::Vector3d body1_position_sol_;
Eigen::Vector3d body2_position_sol_;
};
GTEST_TEST(InverseKinematicsTest, ConstructorWithJointLimits) {
// Constructs an inverse kinematics problem for IIWA robot, make sure that
// the joint limits are imposed when with_joint_limits=true, and the joint
// limits are ignored when with_joint_limits=false.
auto plant = ConstructIiwaPlant(
FindResourceOrThrow(
"drake/manipulation/models/iiwa_description/sdf/"
"iiwa14_no_collision.sdf"),
0.01);
InverseKinematics ik_with_joint_limits(*plant);
InverseKinematics ik_without_joint_limits(*plant, false);
// Now check the joint limits.
const VectorX<double> lower_limits = plant->GetPositionLowerLimits();
const VectorX<double> upper_limits = plant->GetPositionUpperLimits();
// Check if q_test will satisfy the joint limit constraint imposed from the
// IK constructor.
auto q_test_with_joint_limits =
ik_with_joint_limits.get_mutable_prog()->AddBoundingBoxConstraint(
Eigen::VectorXd::Zero(7), Eigen::VectorXd::Zero(7),
ik_with_joint_limits.q());
auto q_test_without_joint_limits =
ik_without_joint_limits.get_mutable_prog()->AddBoundingBoxConstraint(
Eigen::VectorXd::Zero(7), Eigen::VectorXd::Zero(7),
ik_without_joint_limits.q());
auto check_q_with_joint_limits =
[&ik_with_joint_limits,
&q_test_with_joint_limits](const Eigen::VectorXd& q_test) {
q_test_with_joint_limits.evaluator()->UpdateLowerBound(q_test);
q_test_with_joint_limits.evaluator()->UpdateUpperBound(q_test);
return Solve(ik_with_joint_limits.prog()).is_success();
};
auto check_q_without_joint_limits =
[&ik_without_joint_limits,
&q_test_without_joint_limits](const Eigen::VectorXd& q_test) {
q_test_without_joint_limits.evaluator()->UpdateLowerBound(q_test);
q_test_without_joint_limits.evaluator()->UpdateUpperBound(q_test);
return Solve(ik_without_joint_limits.prog()).is_success();
};
for (int i = 0; i < 7; ++i) {
Eigen::VectorXd q_good = Eigen::VectorXd::Zero(7);
q_good(i) = lower_limits(i) * 0.01 + upper_limits(i) * 0.99;
EXPECT_TRUE(check_q_with_joint_limits(q_good));
EXPECT_TRUE(check_q_without_joint_limits(q_good));
q_good(i) = lower_limits(i) * 0.99 + upper_limits(i) * 0.01;
EXPECT_TRUE(check_q_with_joint_limits(q_good));
EXPECT_TRUE(check_q_without_joint_limits(q_good));
Eigen::VectorXd q_bad = q_good;
q_bad(i) = -0.01 * lower_limits(i) + 1.01 * upper_limits(i);
EXPECT_FALSE(check_q_with_joint_limits(q_bad));
EXPECT_TRUE(check_q_without_joint_limits(q_bad));
q_bad(i) = 1.01 * lower_limits(i) - 0.01 * upper_limits(i);
EXPECT_FALSE(check_q_with_joint_limits(q_bad));
EXPECT_TRUE(check_q_without_joint_limits(q_bad));
}
}
TEST_F(TwoFreeBodiesTest, ConstructorAddsUnitQuaterionConstraints) {
ik_.get_mutable_prog()->SetInitialGuess(ik_.q().head<4>(),
Eigen::Vector4d(1, 2, 3, 4));
ik_.get_mutable_prog()->SetInitialGuess(ik_.q().segment<4>(7),
Eigen::Vector4d(.1, .2, .3, .4));
const auto result = Solve(ik_.prog());
EXPECT_TRUE(result.is_success());
Eigen::VectorXd q = result.GetSolution(ik_.q());
EXPECT_NEAR(q.head<4>().squaredNorm(), 1.0, 1e-6);
EXPECT_NEAR(q.segment<4>(7).squaredNorm(), 1.0, 1e-6);
// Test the constructor which takes a Context.
auto context = two_bodies_plant_->CreateDefaultContext();
InverseKinematics ik2(*two_bodies_plant_, context.get());
ik2.get_mutable_prog()->SetInitialGuess(ik2.q().head<4>(),
Eigen::Vector4d(1, 2, 3, 4));
ik2.get_mutable_prog()->SetInitialGuess(
ik2.q().segment<4>(7), Eigen::Vector4d(.1, .2, .3, .4));
const auto result2 = Solve(ik2.prog());
EXPECT_TRUE(result2.is_success());
q = result2.GetSolution(ik2.q());
EXPECT_NEAR(q.head<4>().squaredNorm(), 1.0, 1e-6);
EXPECT_NEAR(q.segment<4>(7).squaredNorm(), 1.0, 1e-6);
}
TEST_F(TwoFreeBodiesTest, PositionConstraint) {
const Eigen::Vector3d p_BQ(0.2, 0.3, 0.5);
const Eigen::Vector3d p_AQ_lower(-0.1, -0.2, -0.3);
const Eigen::Vector3d p_AQ_upper(-0.05, -0.12, -0.28);
ik_.AddPositionConstraint(body1_frame_, p_BQ, body2_frame_, p_AQ_lower,
p_AQ_upper);
ik_.get_mutable_prog()->SetInitialGuess(ik_.q().head<4>(),
Eigen::Vector4d(1, 0, 0, 0));
ik_.get_mutable_prog()->SetInitialGuess(ik_.q().segment<4>(7),
Eigen::Vector4d(1, 0, 0, 0));
const auto result = Solve(ik_.prog());
EXPECT_TRUE(result.is_success());
RetrieveSolution(result);
const Eigen::Vector3d p_AQ = body2_quaternion_sol_.inverse() *
(body1_quaternion_sol_ * p_BQ +
body1_position_sol_ - body2_position_sol_);
const double tol = 1E-6;
EXPECT_TRUE(
(p_AQ.array() <= p_AQ_upper.array() + Eigen::Array3d::Constant(tol))
.all());
EXPECT_TRUE(
(p_AQ.array() >= p_AQ_lower.array() - Eigen::Array3d::Constant(tol))
.all());
}
TEST_F(TwoFreeBodiesTest, PositionCost) {
const Eigen::Vector3d p_AP(-0.1, -0.2, -0.3);
const Eigen::Vector3d p_BQ(0.2, 0.3, 0.5);
auto binding = ik_.AddPositionCost(body1_frame_, p_AP, body2_frame_, p_BQ,
Eigen::Matrix3d::Identity());
// We don't need to test the cost implementation, only that the arguments are
// passed correctly. Just set an arbitrary (but valid) q and evaluate the
// cost.
math::RigidTransform<double> X_WA(
math::RollPitchYaw<double>(0.32, -0.24, -0.51),
Eigen::Vector3d(0.1, 0.3, 0.72));
math::RigidTransform<double> X_WB(math::RollPitchYaw<double>(8.1, 0.42, -0.2),
Eigen::Vector3d(-0.84, 0.2, 1.4));
auto context = two_bodies_plant_->CreateDefaultContext();
two_bodies_plant_->SetFreeBodyPose(
context.get(), two_bodies_plant_->GetBodyByName("body1"), X_WA);
two_bodies_plant_->SetFreeBodyPose(
context.get(), two_bodies_plant_->GetBodyByName("body2"), X_WB);
ik_.get_mutable_prog()->SetInitialGuess(
ik_.q(), two_bodies_plant_->GetPositions(*context));
const Eigen::Vector3d p_AQ = X_WA.inverse() * X_WB * p_BQ;
const Eigen::Vector3d err = p_AQ - p_AP;
const double expected_cost = err.dot(err);
EXPECT_NEAR(ik_.prog().EvalBindingAtInitialGuess(binding)[0], expected_cost,
1e-12);
}
TEST_F(TwoFreeBodiesTest, OrientationConstraint) {
const double angle_bound = 0.05 * M_PI;
const math::RotationMatrix<double> R_AbarA(Eigen::AngleAxisd(
0.1 * M_PI, Eigen::Vector3d(0.2, 0.4, 1.2).normalized()));
const math::RotationMatrix<double> R_BbarB(Eigen::AngleAxisd(
0.2 * M_PI, Eigen::Vector3d(1.2, 2.1, -0.2).normalized()));
ik_.AddOrientationConstraint(body1_frame_, R_AbarA, body2_frame_, R_BbarB,
angle_bound);
ik_.get_mutable_prog()->SetInitialGuess(ik_.q().head<4>(),
Eigen::Vector4d(1, 0, 0, 0));
ik_.get_mutable_prog()->SetInitialGuess(ik_.q().segment<4>(7),
Eigen::Vector4d(1, 0, 0, 0));
const auto result = Solve(ik_.prog());
EXPECT_TRUE(result.is_success());
const auto q_sol = result.GetSolution(ik_.q());
RetrieveSolution(result);
const math::RotationMatrix<double> R_AbarBbar(
body1_quaternion_sol_.inverse() * body2_quaternion_sol_);
const math::RotationMatrix<double> R_AB =
R_AbarA.transpose() * R_AbarBbar * R_BbarB;
const double angle = R_AB.ToAngleAxis().angle();
EXPECT_LE(angle, angle_bound + 1E-6);
}
TEST_F(TwoFreeBodiesTest, OrientationCost) {
const math::RotationMatrix<double> R_AbarA(
math::RollPitchYaw<double>(1, 2, 3));
const math::RotationMatrix<double> R_BbarB(
math::RollPitchYaw<double>(4, 5, 6));
const double c{2.4};
auto binding =
ik_.AddOrientationCost(body1_frame_, R_AbarA, body2_frame_, R_BbarB, c);
// We don't need to test the cost implementation, only that the arguments are
// passed correctly. Just set an arbitrary (but valid) q and evaluate the
// cost.
math::RigidTransform<double> X_WAbar(
math::RollPitchYaw<double>(0.32, -0.24, -0.51),
Eigen::Vector3d(0.1, 0.3, 0.72));
math::RigidTransform<double> X_WBbar(
math::RollPitchYaw<double>(8.1, 0.42, -0.2),
Eigen::Vector3d(-0.84, 0.2, 1.4));
auto context = two_bodies_plant_->CreateDefaultContext();
two_bodies_plant_->SetFreeBodyPose(
context.get(), two_bodies_plant_->GetBodyByName("body1"), X_WAbar);
two_bodies_plant_->SetFreeBodyPose(
context.get(), two_bodies_plant_->GetBodyByName("body2"), X_WBbar);
ik_.get_mutable_prog()->SetInitialGuess(
ik_.q(), two_bodies_plant_->GetPositions(*context));
const math::RotationMatrix<double> R_AB =
(X_WAbar.rotation() * R_AbarA).inverse() * X_WBbar.rotation() * R_BbarB;
const double theta =
math::wrap_to(R_AB.ToAngleAxis().angle(), -M_PI / 2.0, M_PI / 2.0);
EXPECT_NEAR(ik_.prog().EvalBindingAtInitialGuess(binding)[0],
c * (1.0 - cos(theta)), 1e-12);
}
TEST_F(TwoFreeBodiesTest, GazeTargetConstraint) {
const Eigen::Vector3d p_AS(0.01, 0.2, 0.4);
const Eigen::Vector3d n_A(0.2, 0.4, -0.1);
const Eigen::Vector3d p_BT(0.4, -0.2, 1.5);
const double cone_half_angle{0.2 * M_PI};
ik_.AddGazeTargetConstraint(body1_frame_, p_AS, n_A, body2_frame_, p_BT,
cone_half_angle);
ik_.get_mutable_prog()->SetInitialGuess(ik_.q().head<4>(),
Eigen::Vector4d(1, 0, 0, 0));
ik_.get_mutable_prog()->SetInitialGuess(ik_.q().segment<4>(7),
Eigen::Vector4d(1, 0, 0, 0));
const auto result = Solve(ik_.prog());
EXPECT_TRUE(result.is_success());
RetrieveSolution(result);
const Eigen::Vector3d p_WS =
body1_quaternion_sol_ * p_AS + body1_position_sol_;
const Eigen::Vector3d p_WT =
body2_quaternion_sol_ * p_BT + body2_position_sol_;
const Eigen::Vector3d p_ST_A =
body1_quaternion_sol_.inverse() * (p_WT - p_WS);
EXPECT_GE(p_ST_A.dot(n_A),
std::cos(cone_half_angle) * p_ST_A.norm() * n_A.norm() - 1E-3);
}
TEST_F(TwoFreeBodiesTest, AngleBetweenVectorsConstraint) {
const Eigen::Vector3d n_A(0.2, -0.4, 0.9);
const Eigen::Vector3d n_B(1.4, -0.1, 1.8);
const double angle_lower{0.2 * M_PI};
const double angle_upper{0.2 * M_PI};
ik_.AddAngleBetweenVectorsConstraint(body1_frame_, n_A, body2_frame_, n_B,
angle_lower, angle_upper);
ik_.get_mutable_prog()->SetInitialGuess(ik_.q().head<4>(),
Eigen::Vector4d(1, 0, 0, 0));
ik_.get_mutable_prog()->SetInitialGuess(ik_.q().segment<4>(7),
Eigen::Vector4d(1, 0, 0, 0));
const auto result = Solve(ik_.prog());
EXPECT_TRUE(result.is_success());
RetrieveSolution(result);
const Eigen::Vector3d n_A_W = body1_quaternion_sol_ * n_A;
const Eigen::Vector3d n_B_W = body2_quaternion_sol_ * n_B;
const double angle =
std::acos(n_A_W.dot(n_B_W) / (n_A_W.norm() * n_B_W.norm()));
EXPECT_NEAR(angle, angle_lower, 1E-6);
}
TEST_F(TwoFreeBodiesTest, PointToPointDistanceConstraint) {
const Eigen::Vector3d p_B1P1(0.2, -0.4, 0.9);
const Eigen::Vector3d p_B2P2(1.4, -0.1, 1.8);
const double distance_lower{0.2};
const double distance_upper{0.25};
ik_.AddPointToPointDistanceConstraint(body1_frame_, p_B1P1, body2_frame_,
p_B2P2, distance_lower, distance_upper);
ik_.get_mutable_prog()->SetInitialGuess(ik_.q().head<4>(),
Eigen::Vector4d(1, 0, 0, 0));
ik_.get_mutable_prog()->SetInitialGuess(ik_.q().segment<4>(7),
Eigen::Vector4d(1, 0, 0, 0));
const auto result = Solve(ik_.prog());
EXPECT_TRUE(result.is_success());
RetrieveSolution(result);
const Eigen::Vector3d p_WP1 =
body1_position_sol_ + body1_quaternion_sol_ * p_B1P1;
const Eigen::Vector3d p_WP2 =
body2_position_sol_ + body2_quaternion_sol_ * p_B2P2;
const double distance_sol = (p_WP1 - p_WP2).norm();
EXPECT_GE(distance_sol, distance_lower - 1e-6);
EXPECT_LE(distance_sol, distance_upper + 1e-6);
}
TEST_F(TwoFreeBodiesTest, PolyhedronConstraint) {
const Frame<double>& frameF = body1_frame_;
const Frame<double>& frameG = body2_frame_;
Eigen::Matrix<double, 3, 2> p_GP;
p_GP.col(0) << 0.1, 0.2, 0.3;
p_GP.col(1) << 0.4, 0.5, 0.6;
Eigen::Matrix<double, 1, 6> A;
A << 1, 2, 3, 4, 5, 6;
Vector1d b(10);
ik_.AddPolyhedronConstraint(frameF, frameG, p_GP, A, b);
ik_.get_mutable_prog()->SetInitialGuess(ik_.q().head<4>(),
Eigen::Vector4d(1, 0, 0, 0));
ik_.get_mutable_prog()->SetInitialGuess(ik_.q().segment<4>(7),
Eigen::Vector4d(1, 0, 0, 0));
const auto result = Solve(ik_.prog());
EXPECT_TRUE(result.is_success());
auto context = RetrieveSolution(result);
Eigen::Matrix3Xd p_FP(3, p_GP.cols());
two_bodies_plant_->CalcPointsPositions(*context, frameG, p_GP, frameF, &p_FP);
Eigen::Map<Eigen::VectorXd> p_FP_stack(p_FP.data(), 3 * p_FP.cols());
const Eigen::VectorXd y_expected = A * p_FP_stack;
EXPECT_EQ(y_expected.rows(), b.rows());
for (int i = 0; i < b.rows(); ++i) {
EXPECT_LE(y_expected(i), b(i) + 1E-5);
}
}
TEST_F(TwoFreeSpheresTest, MinimumDistanceConstraintTest) {
const double min_distance = 0.1;
InverseKinematics ik(*plant_double_, plant_context_double_);
auto constraint = ik.AddMinimumDistanceConstraint(min_distance);
// The two spheres are colliding in the initial guess.
ik.get_mutable_prog()->SetInitialGuess(ik.q().head<4>(),
Eigen::Vector4d(1, 0, 0, 0));
ik.get_mutable_prog()->SetInitialGuess(ik.q().segment<3>(4),
Eigen::Vector3d(0, 0, 0.01));
ik.get_mutable_prog()->SetInitialGuess(ik.q().segment<4>(7),
Eigen::Vector4d(1, 0, 0, 0));
ik.get_mutable_prog()->SetInitialGuess(ik.q().tail<3>(),
Eigen::Vector3d(0, 0, -0.01));
auto solve_and_check = [&]() {
const solvers::MathematicalProgramResult result = Solve(ik.prog());
EXPECT_TRUE(result.is_success());
const Eigen::Vector3d p_WB1 = result.GetSolution(ik.q().segment<3>(4));
const Eigen::Quaterniond quat_WB1(
result.GetSolution(ik.q()(0)), result.GetSolution(ik.q()(1)),
result.GetSolution(ik.q()(2)), result.GetSolution(ik.q()(3)));
const Eigen::Vector3d p_WB2 = result.GetSolution(ik.q().tail<3>());
const Eigen::Quaterniond quat_WB2(
result.GetSolution(ik.q()(7)), result.GetSolution(ik.q()(8)),
result.GetSolution(ik.q()(9)), result.GetSolution(ik.q()(10)));
const Eigen::Vector3d p_WS1 =
p_WB1 + quat_WB1.toRotationMatrix() * X_B1S1_.translation();
const Eigen::Vector3d p_WS2 =
p_WB2 + quat_WB2.toRotationMatrix() * X_B2S2_.translation();
// This large error is due to the derivative of the penalty function(i.e.,
// the gradient ∂penalty/∂distance) being small near minimum_distance. Hence
// a small violation on the penalty leads to a large violation on the
// minimum_distance.
const double tol = 2e-4;
EXPECT_GE((p_WS1 - p_WS2).norm() - radius1_ - radius2_, min_distance - tol);
};
solve_and_check();
// Now set the two spheres to coincide at the initial guess, and solve again.
ik.get_mutable_prog()->SetInitialGuess(
ik.q().tail<3>(), ik.prog().initial_guess().segment<3>(4));
solve_and_check();
}
} // namespace multibody
} // namespace drake