File size: 33,747 Bytes
2c55b92 | 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 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662 663 664 665 666 667 668 669 670 671 672 673 674 675 676 677 678 679 680 681 682 683 684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699 700 701 702 703 704 705 706 707 708 709 710 711 712 713 714 715 716 717 718 719 720 721 722 723 724 725 726 727 728 729 730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745 746 747 748 749 750 751 752 753 754 755 756 757 758 759 760 761 762 763 764 765 766 767 768 769 770 771 772 773 774 775 776 777 778 779 780 781 782 783 784 785 786 787 788 789 790 791 792 793 794 795 796 797 798 799 800 801 802 803 804 805 806 807 808 809 810 811 812 813 814 815 816 817 818 819 820 821 822 823 824 825 826 827 828 829 830 831 832 833 834 835 836 837 838 839 840 841 842 843 844 845 846 847 848 849 850 851 852 853 854 855 856 857 858 859 860 861 862 863 864 865 866 867 868 869 870 871 872 873 874 875 876 877 878 879 880 881 882 883 884 885 886 887 888 889 890 891 892 893 894 895 896 897 898 899 900 901 902 903 904 905 906 907 908 909 910 911 912 913 914 915 916 917 918 919 920 921 922 923 924 925 926 927 928 929 930 931 932 933 934 935 936 937 938 939 940 941 942 943 944 945 946 947 948 949 950 951 952 953 954 955 956 957 958 959 960 961 962 963 964 965 966 967 968 969 970 971 972 973 974 975 976 977 978 979 980 981 982 983 984 985 986 987 988 989 990 991 992 993 994 995 996 997 998 999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026 1027 1028 1029 1030 1031 1032 1033 1034 1035 1036 1037 1038 1039 1040 1041 1042 1043 1044 1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065 1066 1067 1068 1069 1070 1071 1072 1073 1074 1075 1076 1077 1078 1079 1080 1081 | // Copyright 2022 DeepMind Technologies Limited
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
// Tests for engine/engine_derivative.c.
#include <random>
#include <string>
#include <vector>
#include <gmock/gmock.h>
#include <gtest/gtest.h>
#include <mujoco/mjmodel.h>
#include <mujoco/mujoco.h>
#include "src/engine/engine_core_smooth.h"
#include "src/engine/engine_derivative.h"
#include "src/engine/engine_derivative_fd.h"
#include "src/engine/engine_forward.h"
#include "src/engine/engine_io.h"
#include "src/engine/engine_util_blas.h"
#include "test/fixture.h"
namespace mujoco {
namespace {
using ::std::vector;
using ::testing::Pointwise;
using ::testing::DoubleNear;
using ::testing::Eq;
using ::testing::Each;
using ::testing::NotNull;
using DerivativeTest = MujocoTest;
// errors smaller than this are ignored
static const mjtNum absolute_tolerance = 1e-9;
// corrected relative error
static mjtNum RelativeError(mjtNum a, mjtNum b) {
mjtNum nominator = mjMAX(0, mju_abs(a-b) - absolute_tolerance);
mjtNum denominator = (mju_abs(a) + mju_abs(b) + absolute_tolerance);
return nominator / denominator;
}
// expect two 2D arrays to have elementwise relative error smaller than eps
// return maximum absolute error
static mjtNum CompareMatrices(mjtNum* Actual, mjtNum* Expected,
int nrow, int ncol, mjtNum eps) {
mjtNum max_error = 0;
for (int i=0; i < nrow; i++) {
for (int j=0; j < ncol; j++) {
mjtNum actual = Actual[i*ncol+j];
mjtNum expected = Expected[i*ncol+j];
EXPECT_LT(RelativeError(actual, expected), eps)
<< "error at position (" << i << ", " << j << ")"
<< "\nexpected = " << expected
<< "\nactual = " << actual
<< "\ndiff = " << expected-actual;
max_error = mjMAX(mju_abs(actual-expected), max_error);
}
}
return max_error;
}
static const char* const kEnergyConservingPendulumPath =
"engine/testdata/derivative/energy_conserving_pendulum.xml";
static const char* const kTumblingThinObjectPath =
"engine/testdata/derivative/tumbling_thin_object.xml";
static const char* const kTumblingThinObjectEllipsoidPath =
"engine/testdata/derivative/tumbling_thin_object_ellipsoid.xml";
static const char* const kDampedActuatorsPath =
"engine/testdata/derivative/damped_actuators.xml";
static const char* const kDamperActuatorsPath =
"engine/testdata/actuation/damper.xml";
static const char* const kDampedPendulumPath =
"engine/testdata/derivative/damped_pendulum.xml";
static const char* const kLinearPath =
"engine/testdata/derivative/linear.xml";
static const char* const kModelPath = "testdata/model.xml";
// compare analytic and finite-difference d_smooth/d_qvel
TEST_F(DerivativeTest, SmoothDvel) {
// run test on all models
for (const char* local_path : {kEnergyConservingPendulumPath,
kTumblingThinObjectPath,
kDampedActuatorsPath,
kDamperActuatorsPath}) {
const std::string xml_path = GetTestDataFilePath(local_path);
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, nullptr, 0);
int nD = model->nD;
mjData* data = mj_makeData(model);
for (mjtJacobian sparsity : {mjJAC_DENSE, mjJAC_SPARSE}) {
// set sparsity
model->opt.jacobian = sparsity;
// take 100 steps so we have some velocities, then call forward
mj_resetData(model, data);
if (model->nu) {
data->ctrl[0] = 0.1;
}
for (int i=0; i < 100; i++) {
mj_step(model, data);
}
mj_forward(model, data);
// construct sparse structure in d->D_xxx, compute analytical qDeriv
mju_zero(data->qDeriv, nD);
mjd_smooth_vel(model, data, /*flg_bias=*/true);
// expect derivatives to be non-zero, make copy of qDeriv as a vector
EXPECT_GT(mju_norm(data->qDeriv, nD), 0);
vector<mjtNum> qDerivAnalytic = AsVector(data->qDeriv, nD);
// compute finite-difference derivatives
mjtNum eps = 1e-7;
mju_zero(data->qDeriv, nD);
mjd_smooth_velFD(model, data, eps);
// expect FD and analytic derivatives to be numerically different
EXPECT_NE(mju_norm(data->qDeriv, nD),
mju_norm(qDerivAnalytic.data(), nD));
// expect FD and analytic derivatives to be similar to eps precision
EXPECT_THAT(AsVector(data->qDeriv, nD),
Pointwise(DoubleNear(eps), qDerivAnalytic));
}
mj_deleteData(data);
mj_deleteModel(model);
}
}
// disabled actuators do not contribute to d_qfrc_actuator/d_qvel
TEST_F(DerivativeTest, DisabledActuators) {
// model with only a position actuator
static constexpr char xml1[] = R"(
<mujoco>
<option integrator="implicitfast"/>
<worldbody>
<body>
<joint name="joint" type="slide"/>
<geom size=".1"/>
</body>
</worldbody>
<actuator>
<position joint="joint" group="1" kp="2000" kv="200"/>
</actuator>
</mujoco>
)";
mjModel* m1 = LoadModelFromString(xml1);
mjData* d1 = mj_makeData(m1);
d1->ctrl[0] = 6;
while (d1->time < 1)
mj_step(m1, d1);
// model with a position actuator and an intvelocity actuator
static constexpr char xml2[] = R"(
<mujoco>
<option integrator="implicitfast" actuatorgroupdisable="2"/>
<worldbody>
<body>
<joint name="joint" type="slide"/>
<geom size=".1"/>
</body>
</worldbody>
<actuator>
<position joint="joint" group="1" kp="2000" kv="200"/>
<intvelocity joint="joint" group="2" kp="2000" kv="200" actrange="-6 6"/>
</actuator>
</mujoco>
)";
mjModel* m2 = LoadModelFromString(xml2);
mjData* d2 = mj_makeData(m2);
d2->ctrl[0] = 6;
d2->ctrl[1] = 6;
while (d2->time < 1)
mj_step(m2, d2);
// expect same qvel in both models
EXPECT_EQ(d1->qvel[0], d2->qvel[0]);
mj_deleteData(d2);
mj_deleteModel(m2);
mj_deleteData(d1);
mj_deleteModel(m1);
}
// actuator order has no effect
TEST_F(DerivativeTest, ActuatorOrder) {
// model with stateful actuator first
static constexpr char xml1[] = R"(
<mujoco>
<option integrator="implicitfast"/>
<worldbody>
<body>
<joint name="0" type="slide" range="-1 1"/>
<geom size=".1"/>
</body>
<body pos="1 0 0">
<joint name="1" type="slide" range="-1 1"/>
<geom size=".1"/>
</body>
</worldbody>
<actuator>
<muscle joint="0" ctrlrange="0 6"/>
<damper joint="1" kv="200" ctrlrange="0 6"/>
</actuator>
</mujoco>
)";
char error[1024];
mjModel* m1 = LoadModelFromString(xml1, error, sizeof(error));
ASSERT_THAT(m1, NotNull()) << "Failed to load model: " << error;
mjData* d1 = mj_makeData(m1);
d1->ctrl[0] = 6;
d1->ctrl[1] = 6;
while (d1->time < 1)
mj_step(m1, d1);
// model with stateful actuator second
static constexpr char xml2[] = R"(
<mujoco>
<option integrator="implicitfast"/>
<worldbody>
<body>
<joint name="0" type="slide" range="-1 1"/>
<geom size=".1"/>
</body>
<body pos="1 0 0">
<joint name="1" type="slide" range="-1 1"/>
<geom size=".1"/>
</body>
</worldbody>
<actuator>
<damper joint="1" kv="200" ctrlrange="0 6"/>
<muscle joint="0" ctrlrange="0 6"/>
</actuator>
</mujoco>
)";
mjModel* m2 = LoadModelFromString(xml2, error, sizeof(error));
ASSERT_THAT(m2, NotNull()) << "Failed to load model: " << error;
mjData* d2 = mj_makeData(m2);
d2->ctrl[0] = 6;
d2->ctrl[1] = 6;
while (d2->time < 1)
mj_step(m2, d2);
// expect same qvel in both models
EXPECT_EQ(d1->qvel[0], d2->qvel[0]);
EXPECT_EQ(d1->qvel[1], d2->qvel[1]);
mj_deleteData(d2);
mj_deleteModel(m2);
mj_deleteData(d1);
mj_deleteModel(m1);
}
// compare analytic and fin-diff d_qfrc_passive/d_qvel
TEST_F(DerivativeTest, PassiveDvel) {
for (const char* local_path : {kTumblingThinObjectPath,
kTumblingThinObjectEllipsoidPath}) {
// load model
const std::string xml_path = GetTestDataFilePath(local_path);
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, nullptr, 0);
int nD = model->nD;
mjData* data = mj_makeData(model);
// allocate Jacobians
mjtNum* qDerivAnalytic = (mjtNum*) mju_malloc(sizeof(mjtNum)*nD);
mjtNum* qDerivFD = (mjtNum*) mju_malloc(sizeof(mjtNum)*nD);
for (mjtJacobian sparsity : {mjJAC_DENSE, mjJAC_SPARSE}) {
// set sparsity
model->opt.jacobian = sparsity;
// take 100 steps so we have some velocities, then call forward
mj_resetData(model, data);
for (int i=0; i < 100; i++) {
mj_step(model, data);
}
mj_forward(model, data);
// get analytic derivatives
mju_copy(qDerivAnalytic, data->qDeriv, nD);
// clear qDeriv, get finite-difference derivatives
mju_zero(data->qDeriv, nD);
mju_zero(qDerivFD, nD);
mjtNum eps = 1e-6;
mjd_passive_velFD(model, data, eps);
// expect FD and analytic derivatives to be similar to tol precision
mjtNum tol = 1e-4;
EXPECT_THAT(AsVector(data->qDeriv, nD),
Pointwise(DoubleNear(tol), AsVector(qDerivAnalytic, nD)));
}
mju_free(qDerivFD);
mju_free(qDerivAnalytic);
mj_deleteData(data);
mj_deleteModel(model);
}
}
// ----------------------- derivatives of mj_step() ----------------------------
// mj_stepSkip computes the same next state as mj_step
TEST_F(DerivativeTest, StepSkip) {
const std::string xml_path = GetTestDataFilePath(kDampedPendulumPath);
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, nullptr, 0);
mjData* data = mj_makeData(model);
int nq = model->nq;
int nv = model->nv;
// disable warm-starts so we don't need to save qacc_warmstart
model->opt.disableflags |= mjDSBL_WARMSTART;
for (const mjtIntegrator integrator : {mjINT_EULER,
mjINT_IMPLICIT,
mjINT_IMPLICITFAST}) {
model->opt.integrator = integrator;
// reset, take 20 steps
mj_resetData(model, data);
for (int i=0; i < 20; i++) {
mj_step(model, data);
}
// denormalize the quat, just to see that it doesn't make a difference
for (int j=0; j < model->njnt; j++) {
if (model->jnt_type[j] == mjJNT_BALL) {
int adr = model->jnt_qposadr[j];
for (int k=0; k < 4; k++) {
data->qpos[adr + k] *= 8;
}
}
}
// save state
vector<mjtNum> qpos = AsVector(data->qpos, nq);
vector<mjtNum> qvel = AsVector(data->qvel, nv);
// take one more step, save next state
mj_step(model, data);
vector<mjtNum> qpos_next = AsVector(data->qpos, nq);
vector<mjtNum> qvel_next = AsVector(data->qvel, nv);
// reset state, take step again, compare (assert mj_step is deterministic)
mju_copy(data->qpos, qpos.data(), nq);
mju_copy(data->qvel, qvel.data(), nv);
mj_step(model, data);
EXPECT_THAT(AsVector(data->qpos, nq), Pointwise(Eq(), qpos_next));
EXPECT_THAT(AsVector(data->qvel, nv), Pointwise(Eq(), qvel_next));
// reset state, change ctrl, call mj_stepSkip, save next state
mju_copy(data->qpos, qpos.data(), nq);
mju_copy(data->qvel, qvel.data(), nv);
data->ctrl[0] = 1;
mj_stepSkip(model, data, mjSTAGE_VEL, 0); // skipping both POS and VEL
vector<mjtNum> qpos_next_dctrl = AsVector(data->qpos, nq);
vector<mjtNum> qvel_next_dctrl = AsVector(data->qvel, nv);
// reset state (ctrl remains unchanged), call full mj_step, compare
mju_copy(data->qpos, qpos.data(), nq);
mju_copy(data->qvel, qvel.data(), nv);
mj_step(model, data);
EXPECT_THAT(AsVector(data->qpos, nq), Pointwise(Eq(), qpos_next_dctrl));
EXPECT_THAT(AsVector(data->qvel, nv), Pointwise(Eq(), qvel_next_dctrl));
// reset state, change velocity, call mj_stepSkip, save next state
mju_copy(data->qpos, qpos.data(), nq);
mju_copy(data->qvel, qvel.data(), nv);
data->qvel[0] += 1;
mj_stepSkip(model, data, mjSTAGE_POS, 0); // skipping POS
vector<mjtNum> qpos_next_dvel = AsVector(data->qpos, nq);
vector<mjtNum> qvel_next_dvel = AsVector(data->qvel, nv);
// reset state, change velocity, call full mj_step, compare
mju_copy(data->qpos, qpos.data(), nq);
mju_copy(data->qvel, qvel.data(), nv);
data->qvel[0] += 1;
mj_step(model, data);
EXPECT_THAT(AsVector(data->qpos, nq), Pointwise(Eq(), qpos_next_dvel));
EXPECT_THAT(AsVector(data->qvel, nv), Pointwise(Eq(), qvel_next_dvel));
}
mj_deleteData(data);
mj_deleteModel(model);
}
// Analytic transition matrices for linear dynamical system xn = A*x + B*u
// given modified mass matrix H (`data->qH`) and
// Ac = H^-1 [diag(-stiffness) diag(-damping)]
// we have
// A = eye(2*nv) + dt [dt*Ac + [zeros(3) eye(3)]; Ac]
// given the moment arm matrix K (`data->actuator_moment`) and Bc = H^-1 K
// B = dt*[Bc*dt; Bc]
static void LinearSystem(const mjModel* m, mjData* d, mjtNum* A, mjtNum* B) {
int nv = m->nv, nu = m->nu;
mjtNum dt = m->opt.timestep;
mj_markStack(d);
// === state-transition matrix A
if (A) {
mjtNum *Ac = mj_stackAllocNum(d, 2*nv*nv);
// Ac = H^-1 [diag(-stiffness) diag(-damping)]
mju_zero(Ac, 2*nv*nv);
for (int i=0; i < nv; i++) {
Ac[i*nv + i] = -m->jnt_stiffness[i];
Ac[nv*nv + i*nv + i] = -m->dof_damping[i];
}
mj_solveLD(Ac, d->qH, d->qHDiagInv, nv, 2*nv,
d->M_rownnz, d->M_rowadr, d->M_colind);
// A = [dt*Ac; Ac]
mju_transpose(A, Ac, 2*nv, nv);
mju_scl(A, A, dt, nv*2*nv);
mju_transpose(A+2*nv*nv, Ac, 2*nv, nv);
// Add eye(nv) to top right quadrant of A
for (int i=0; i < nv; i++) {
A[i*2*nv + nv + i] += 1;
}
// A *= dt
mju_scl(A, A, dt, 2*nv*2*nv);
// A += eye(2*nv)
for (int i=0; i < 2*nv; i++) {
A[i*2*nv + i] += 1;
}
}
// === control-transition matrix B
if (B) {
mjtNum *Bc = mj_stackAllocNum(d, nu*nv);
mjtNum *BcT = mj_stackAllocNum(d, nv*nu);
mju_sparse2dense(Bc, d->actuator_moment, nu, nv, d->moment_rownnz,
d->moment_rowadr, d->moment_colind);
mj_solveLD(Bc, d->qH, d->qHDiagInv, nv, nu,
d->M_rownnz, d->M_rowadr, d->M_colind);
mju_transpose(BcT, Bc, nu, nv);
mju_scl(B, BcT, dt*dt, nu*nv);
mju_scl(B+nu*nv, BcT, dt, nu*nv);
}
mj_freeStack(d);
}
// compare FD derivatives to analytic derivatives of linear dynamical system
TEST_F(DerivativeTest, LinearSystem) {
const std::string xml_path = GetTestDataFilePath(kLinearPath);
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, nullptr, 0);
mjData* data = mj_makeData(model);
int nv = model->nv, nu = model->nu;
// set ctrl, integrate for 20 steps
data->ctrl[0] = .1;
data->ctrl[1] = -.1;
for (int i=0; i < 20; i++) {
mj_step(model, data);
}
// analytic A and B
mjtNum* A = (mjtNum*) mju_malloc(sizeof(mjtNum)*2*nv*2*nv);
mjtNum* B = (mjtNum*) mju_malloc(sizeof(mjtNum)*2*nv*nu);
LinearSystem(model, data, A, B);
// uncomment for debugging:
// PrintMatrix(A, 2*nv, 2*nv);
// PrintMatrix(B, 2*nv, nu);
// forward differenced A and B
mjtNum eps = 1e-6;
mjtNum* AFD = (mjtNum*) mju_malloc(sizeof(mjtNum)*2*nv*2*nv);
mjtNum* BFD = (mjtNum*) mju_malloc(sizeof(mjtNum)*2*nv*nu);
mjd_transitionFD(model, data, eps, /*centered=*/0,
AFD, BFD, nullptr, nullptr);
// uncomment for debugging:
// PrintMatrix(AFD, 2*nv, 2*nv);
// PrintMatrix(BFD, 2*nv, nu);
// expect FD and analytic derivatives to be similar to eps precision
CompareMatrices(A, AFD, 2*nv, 2*nv, eps);
CompareMatrices(B, BFD, 2*nv, nu, eps);
// central differenced A and B
mjtNum* AFDc = (mjtNum*) mju_malloc(sizeof(mjtNum)*2*nv*2*nv);
mjtNum* BFDc = (mjtNum*) mju_malloc(sizeof(mjtNum)*2*nv*nu);
mjd_transitionFD(model, data, eps, /*centered=*/1,
AFDc, BFDc, nullptr, nullptr);
// expect central derivatives to be equal to forward differences
CompareMatrices(AFD, AFDc, 2*nv, 2*nv, eps);
CompareMatrices(BFD, BFDc, 2*nv, nu, eps);
mju_free(BFDc);
mju_free(AFDc);
mju_free(BFD);
mju_free(AFD);
mju_free(B);
mju_free(A);
mj_deleteData(data);
mj_deleteModel(model);
}
// check ctrl derivatives at the range limit
TEST_F(DerivativeTest, ClampedCtrlDerivatives) {
const std::string xml_path = GetTestDataFilePath(kLinearPath);
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, nullptr, 0);
mjData* data = mj_makeData(model);
int nv = model->nv, nu = model->nu;
// set ctrl, integrate for 20 steps
data->ctrl[0] = .1;
data->ctrl[1] = -.1;
for (int i=0; i < 20; i++) {
mj_step(model, data);
}
// analytic B
mjtNum* B = (mjtNum*) mju_malloc(sizeof(mjtNum)*2*nv*nu);
LinearSystem(model, data, nullptr, B);
// forward differenced A and B
mjtNum eps = 1e-6;
mjtNum* BFD = (mjtNum*) mju_malloc(sizeof(mjtNum)*2*nv*nu);
// set ctrl to the limits, request forward differences
data->ctrl[0] = 1;
data->ctrl[1] = -1;
mjd_transitionFD(model, data, eps, /*centered=*/0,
nullptr, BFD, nullptr, nullptr);
// expect FD and analytic derivatives to be similar to eps precision
CompareMatrices(B, BFD, 2*nv, nu, eps);
// ctrl remains at limits, request central differences
mjd_transitionFD(model, data, eps, /*centered=*/1,
nullptr, BFD, nullptr, nullptr);
// expect FD and analytic derivatives to be similar to eps precision
CompareMatrices(B, BFD, 2*nv, nu, eps);
// set ctrl beyond limits, request forward differences
data->ctrl[0] = 2;
data->ctrl[1] = -2;
mjd_transitionFD(model, data, eps, /*centered=*/0,
nullptr, BFD, nullptr, nullptr);
// expect derivatives to be 0
EXPECT_THAT(AsVector(BFD, 2*nv*nu), Each(Eq(0.0)));
// expect ctrl to remain unchanged (despite internal clamping)
EXPECT_EQ(data->ctrl[0], 2.0);
EXPECT_EQ(data->ctrl[1], -2.0);
// ctrl remains beyond limits, request centered differences
mjd_transitionFD(model, data, eps, /*centered=*/1,
nullptr, BFD, nullptr, nullptr);
// expect derivatives to be 0
EXPECT_THAT(AsVector(BFD, 2*nv*nu), Each(Eq(0.0)));
mju_free(BFD);
mju_free(B);
mj_deleteData(data);
mj_deleteModel(model);
}
// compare FD sensor derivatives to analytic derivatives
TEST_F(DerivativeTest, SensorDerivatives) {
static constexpr char xml[] = R"(
<mujoco>
<worldbody>
<body>
<joint name="joint" type="slide"/>
<geom size=".1"/>
</body>
</worldbody>
<actuator>
<general name="actuator" joint="joint" gainprm="3"/>
</actuator>
<sensor>
<jointpos joint="joint"/>
<jointvel joint="joint"/>
<actuatorfrc actuator="actuator"/>
</sensor>
</mujoco>
)";
mjModel* model = LoadModelFromString(xml);
int nv = model->nv, nu = model->nu, ns = model->nsensordata;
mjData* data = mj_makeData(model);
// finite differenced C and D
mjtNum eps = 1e-6;
mjtNum* CFD = (mjtNum*) mju_malloc(sizeof(mjtNum)*ns*2*nv);
mjtNum* DFD = (mjtNum*) mju_malloc(sizeof(mjtNum)*ns*nu);
mjd_transitionFD(model, data, eps, /*centered=*/0,
nullptr, nullptr, CFD, DFD);
// expected analytic C and D
mjtNum C[6] = {
1, 0,
0, 1,
0, 0
};
mjtNum D[3] = {
0,
0,
3,
};
// compare expected and actual values
CompareMatrices(CFD, C, ns, 2*nv, eps);
CompareMatrices(DFD, D, ns, nu, eps);
mju_free(DFD);
mju_free(CFD);
mj_deleteData(data);
mj_deleteModel(model);
}
// if sensor derivatives aren't requested, don't compute sensors
TEST_F(DerivativeTest, SensorSkip) {
static constexpr char xml[] = R"(
<mujoco>
<worldbody>
<body>
<joint name="joint" type="slide"/>
<geom size=".1"/>
</body>
</worldbody>
<actuator>
<general name="actuator" joint="joint" gainprm="3"/>
</actuator>
<sensor>
<jointpos joint="joint"/>
</sensor>
</mujoco>
)";
mjModel* model = LoadModelFromString(xml);
int nv = model->nv, nu = model->nu;
mjData* data = mj_makeData(model);
// set a sentinel value in the sensor
data->sensordata[0] = 1337;
// finite differenced B
mjtNum eps = 1e-6;
mjtNum* BFD = (mjtNum*) mju_malloc(sizeof(mjtNum)*2*nv*nu);
mjd_transitionFD(model, data, eps, /*centered=*/0,
nullptr, BFD, nullptr, nullptr);
EXPECT_EQ(data->sensordata[0], 1337) << "sensors should not be recomputed";
mju_free(BFD);
mj_deleteData(data);
mj_deleteModel(model);
}
// derivatives don't mutate the state
TEST_F(DerivativeTest, NoStateMutation) {
const std::string xml_path = GetTestDataFilePath(kModelPath);
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, nullptr, 0);
ASSERT_THAT(model, NotNull());
mjData* data0 = mj_makeData(model);
mjData* data = mj_makeData(model);
int nv = model->nv, nu = model->nu, na = model->na, ns = model->nsensordata;
// set time
data->time = data0->time = 0.5;
for (int i=0; i < nv; i++) {
data->qpos[i] = data0->qpos[i] = (mjtNum) i+1;
data->qvel[i] = data0->qvel[i] = (mjtNum) i+2;
}
// set ctrl
for (int i=0; i < nu; i++) {
data->ctrl[i] = data0->ctrl[i] = (mjtNum) i+1;
}
// set act
for (int i=0; i < na; i++) {
data->act[i] = data0->act[i] = (mjtNum) i+1;
}
// allocate Jacobians, call derivatives
int ndx = nv+nv+na;
mjtNum* A = (mjtNum*) mju_malloc(sizeof(mjtNum)*ndx*ndx);
mjtNum* B = (mjtNum*) mju_malloc(sizeof(mjtNum)*ndx*nu);
mjtNum* C = (mjtNum*) mju_malloc(sizeof(mjtNum)*ns*ndx);
mjtNum* D = (mjtNum*) mju_malloc(sizeof(mjtNum)*ns*nu);
mjtNum eps = 1e-6;
mjd_transitionFD(model, data, eps, /*centered=*/0, A, B, C, D);
// compare states in data and data0
EXPECT_EQ(data->time, data0->time);
EXPECT_EQ(AsVector(data->qpos, model->nq), AsVector(data0->qpos, model->nq));
EXPECT_EQ(AsVector(data->qvel, nv), AsVector(data0->qvel, nv));
EXPECT_EQ(AsVector(data->act, na), AsVector(data0->act, na));
EXPECT_EQ(AsVector(data->ctrl, nu), AsVector(data0->ctrl, nu));
mju_free(D);
mju_free(C);
mju_free(B);
mju_free(A);
mj_deleteData(data);
mj_deleteData(data0);
mj_deleteModel(model);
}
// compare dense and sparse derivatives of qfrc_bias (RNE)
TEST_F(DerivativeTest, DenseSparseRneEquivalent) {
// run test on all models
for (const char* local_path : {kEnergyConservingPendulumPath,
kTumblingThinObjectPath,
kDampedActuatorsPath,
kDamperActuatorsPath}) {
const std::string xml_path = GetTestDataFilePath(local_path);
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, nullptr, 0);
int nD = model->nD;
mjtNum* qDeriv = (mjtNum*) mju_malloc(sizeof(mjtNum)*nD);
mjData* data = mj_makeData(model);
// take 100 steps so we have some velocities, then call forward
mj_resetData(model, data);
if (model->nu) {
data->ctrl[0] = 0.1;
}
for (int i=0; i < 100; i++) {
mj_step(model, data);
}
mj_forward(model, data);
// compute qDeriv with sparse function, make local copy
mjd_smooth_vel(model, data, /*flg_bias=*/1);
mju_copy(qDeriv, data->qDeriv, nD);
// re-compute with dense function
mju_zero(data->qDeriv, model->nD);
mjd_actuator_vel(model, data);
mjd_passive_vel(model, data);
mjd_rne_vel_dense(model, data);
// expect dense and sparse derivatives to be similar to eps precision
mjtNum eps = 1e-12;
EXPECT_THAT(AsVector(data->qDeriv, nD),
Pointwise(DoubleNear(eps), AsVector(qDeriv, nD)));
mj_deleteData(data);
mju_free(qDeriv);
mj_deleteModel(model);
}
}
// compare FD inverse derivatives to analytic derivatives of linear system
TEST_F(DerivativeTest, LinearSystemInverse) {
const std::string xml_path = GetTestDataFilePath(kLinearPath);
mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, nullptr, 0);
mjData* data = mj_makeData(model);
int nv = model->nv;
int ns = model->nsensordata;
int nM = model->nM;
vector<mjtNum> DfDq(nv*nv);
vector<mjtNum> DfDv(nv*nv);
vector<mjtNum> DfDa(nv*nv);
vector<mjtNum> DsDq(nv*ns);
vector<mjtNum> DsDv(nv*ns);
vector<mjtNum> DsDa(nv*ns);
vector<mjtNum> DmDq(nv*nM);
// call mj_forward to get accelerations at initial state
mj_forward(model, data);
// get derivatives
mjtNum eps = 1e-6;
mjtByte flg_actuation = 0;
mjd_inverseFD(model, data, eps, flg_actuation,
DfDq.data(), DfDv.data(), DfDa.data(),
DsDq.data(), DsDv.data(), DsDa.data(),
DmDq.data());
// expect that position derivatives are the stiffnesses
vector<mjtNum> DfDq_expect = {model->jnt_stiffness[0], 0, 0,
0, model->jnt_stiffness[1], 0,
0, 0, model->jnt_stiffness[2]};
EXPECT_THAT(DfDq, Pointwise(DoubleNear(eps), DfDq_expect));
// expect that velocity derivatives are the dampings
vector<mjtNum> DfDv_expect = {model->dof_damping[0], 0, 0,
0, model->dof_damping[1], 0,
0, 0, model->dof_damping[2]};
EXPECT_THAT(DfDv, Pointwise(DoubleNear(eps), DfDv_expect));
// expect that acceleration derivatives are the mass matrix
vector<mjtNum> DfDa_expect(nv*nv, 0);
mj_fullM(model, DfDa_expect.data(), data->qM);
EXPECT_THAT(DfDa, Pointwise(DoubleNear(eps), DfDa_expect));
// expect that sensor derivatives w.r.t position only see sensor 1 at dof 0
vector<mjtNum> DsDq_expect(nv*ns, 0);
int dof_index = 0;
int sensordata_index = model->sensor_adr[1];
DsDq_expect[dof_index*ns + sensordata_index] = 1;
EXPECT_THAT(DsDq, Pointwise(DoubleNear(eps), DsDq_expect));
// expect that sensor derivatives w.r.t velocity only see sensor 0 at dof 1
vector<mjtNum> DsDv_expect(nv*ns, 0);
dof_index = 1;
sensordata_index = model->sensor_adr[0];
DsDv_expect[dof_index*ns + sensordata_index] = 1;
EXPECT_THAT(DsDv, Pointwise(DoubleNear(eps), DsDv_expect));
// expect that sensor derivatives w.r.t acceleration see the accelerometer
// in the y-axis, affected by both dof 0 and dof 1
vector<mjtNum> DsDa_expect(nv*ns, 0);
dof_index = 0;
sensordata_index = model->sensor_adr[2] + 1;
DsDa_expect[dof_index*ns + sensordata_index] = 1;
dof_index = 1;
DsDa_expect[dof_index*ns + sensordata_index] = 1;
EXPECT_THAT(DsDa, Pointwise(DoubleNear(eps), DsDa_expect));
// expect that mass matrix derivatives are zero
vector<mjtNum> DmDq_expect(nv*nM, 0);
EXPECT_THAT(DmDq, Pointwise(DoubleNear(eps), DmDq_expect));
mj_deleteData(data);
mj_deleteModel(model);
}
// utility: generate two random quaternions with a given angle difference
void randomQuatPair(mjtNum qa[4], mjtNum qb[4], mjtNum angle, int seed) {
// make distribution using seed
std::mt19937_64 rng;
rng.seed(seed);
std::normal_distribution<double> dist(0, 1);
// sample qa = qb
for (int i=0; i < 4; i++) {
qa[i] = qb[i] = dist(rng);
}
mju_normalize4(qa);
mju_normalize4(qb);
// integrate qb in random direction by angle
mjtNum dir[3];
for (int i=0; i < 3; i++) {
dir[i] = dist(rng);
}
mju_normalize3(dir);
mju_quatIntegrate(qb, dir, angle);
}
// utility: finite-difference Jacobians of mju_subQuat
static void subQuatFD(mjtNum Da[9], mjtNum Db[9],
const mjtNum qa[4], const mjtNum qb[4], mjtNum eps) {
// subQuat
mjtNum y[3];
mju_subQuat(y, qa, qb);
mjtNum dq[3]; // nudge input direction
mjtNum dqa[4]; // nudged qa input
mjtNum dqb[4]; // nudged qb input
mjtNum dy[3]; // nudged output
mjtNum DaT[9]; // Da transposed
mjtNum DbT[9]; // Db transposed
for (int i = 0; i < 3; i++) {
// perturbation
mju_zero3(dq);
dq[i] = 1.0;
// Jacobian: d_y / d_qa
mju_copy4(dqa, qa);
mju_quatIntegrate(dqa, dq, eps);
mju_subQuat(dy, dqa, qb);
mju_sub3(DaT + i * 3, dy, y);
mju_scl3(DaT + i * 3, DaT + i * 3, 1.0 / eps);
// Jacobian: d_y / d_qb
mju_copy4(dqb, qb);
mju_quatIntegrate(dqb, dq, eps);
mju_subQuat(dy, qa, dqb);
mju_sub3(DbT + i * 3, dy, y);
mju_scl3(DbT + i * 3, DbT + i * 3, 1.0 / eps);
}
// transpose result
mju_transpose(Da, DaT, 3, 3);
mju_transpose(Db, DbT, 3, 3);
}
TEST_F(DerivativeTest, SubQuat) {
const int nrepeats = 10; // number of repeats
const mjtNum eps = 1e-7; // epsilon for finite-differencing and comparison
int seed = 1;
for (int i = 0; i < nrepeats; i++) {
for (mjtNum angle : {0.0, 1e-9, 1e-5, 1e-2, 1.0, 4.0}) {
// random quaternions
mjtNum qa[4];
mjtNum qb[4];
// make random quaternion pair with given relative angle
randomQuatPair(qa, qb, angle, seed++);
// analytic Jacobians
mjtNum Da[9]; // d_subQuat(qa, qb) / d_qa
mjtNum Db[9]; // d_subQuat(qa, qb) / d_qb
mjd_subQuat(qa, qb, Da, Db);
// finite-differenced Jacobians
mjtNum DaFD[9];
mjtNum DbFD[9];
subQuatFD(DaFD, DbFD, qa, qb, eps);
// expect numerical equality
EXPECT_THAT(AsVector(DaFD, 9),
Pointwise(DoubleNear(eps), AsVector(Da, 9)));
EXPECT_THAT(AsVector(DbFD, 9),
Pointwise(DoubleNear(eps), AsVector(Db, 9)));
}
}
}
// utility: random quaternion, 3D velocity
static void randomQuatVel(mjtNum quat[4], mjtNum vel[3], int seed) {
// make distribution using seed
std::mt19937_64 rng;
rng.seed(seed);
std::normal_distribution<double> dist(0, 1);
// sample quat
for (int i=0; i < 4; i++) {
quat[i] = dist(rng);
}
mju_normalize4(quat);
// sample vel
for (int i=0; i < 3; i++) {
vel[i] = dist(rng);
}
}
// utility: finite-difference Jacobians of mju_quatIntegrate
void mjd_quatIntegrateFD(mjtNum Dquat[9], mjtNum Ds[9],
mjtNum Dvel[9], mjtNum Dh[3],
const mjtNum quat[4], const mjtNum vel[3],
mjtNum h, mjtNum eps) {
// compute y, output of mju_quatIntegrate(quat, vel, h)
mjtNum y[4] = {quat[0], quat[1], quat[2], quat[3]};
mju_quatIntegrate(y, vel, h);
mjtNum dx[3]; // nudged tangent-space input
mjtNum dq[4]; // quat output
mjtNum dy[3]; // nudged tangent-space output
mjtNum DquatT[9]; // Dquat transposed
mjtNum DsT[9]; // Ds transposed
mjtNum DvelT[9]; // Dvel transposed
for (int i = 0; i < 3; i++) {
// perturbation
mju_zero3(dx);
dx[i] = 1.0;
// d_y / d_quat
mju_copy4(dq, quat);
mju_quatIntegrate(dq, dx, eps); // nudge dq
mju_quatIntegrate(dq, vel, h); // compute nudged
mju_subQuat(dy, dq, y); // subtract
mju_scl3(DquatT + i * 3, dy, 1.0 / eps);
// d_y / d_sv (scaled velocity)
mju_copy4(dq, quat);
mjtNum dsv[3] = {vel[0]*h, vel[1]*h, vel[2]*h};
mju_addToScl3(dsv, dx, eps); // nudge dsv
mju_quatIntegrate(dq, dsv, 1.0); // compute nudged
mju_subQuat(dy, dq, y); // subtract
mju_scl3(DsT + i * 3, dy, 1.0 / eps);
// d_y / d_v (unscaled velocity)
mju_copy4(dq, quat);
mjtNum dv[3] = {vel[0], vel[1], vel[2]};
mju_addToScl3(dv, dx, eps); // nudge dv
mju_quatIntegrate(dq, dv, h); // compute nudged
mju_subQuat(dy, dq, y); // subtract
mju_scl3(DvelT + i * 3, dy, 1.0 / eps);
}
// d_y / d_h (unscaled velocity)
mju_copy4(dq, quat);
mju_quatIntegrate(dq, vel, h + eps); // compute nudged
mju_subQuat(dy, dq, y); // subtract
mju_scl3(Dh, dy, 1.0 / eps);
// transpose
mju_transpose(Dquat, DquatT, 3, 3);
mju_transpose(Ds, DsT, 3, 3);
mju_transpose(Dvel, DsT, 3, 3);
}
TEST_F(DerivativeTest, quatIntegrate) {
const int nrepeats = 10; // number of repeats
const mjtNum eps = 1e-7; // epsilon for finite-differencing and comparison
int seed = 1;
for (int i = 0; i < nrepeats; i++) {
for (mjtNum h : {0.0, 1e-9, 1e-5, 1e-2, 1.0, 4.0}) {
// make random quaternion and velocity
mjtNum quat[4];
mjtNum vel[3];
randomQuatVel(quat, vel, seed++);
// analytic Jacobians
mjtNum Dquat[9]; // d_quatIntegrate(quat, vel, h) / d_quat
mjtNum Dvel[9]; // d_quatIntegrate(quat, vel, h) / d_vel
mjtNum Dh[3]; // d_quatIntegrate(quat, vel, h) / d_h
mjd_quatIntegrate(vel, h, Dquat, Dvel, Dh);
// finite-differenced Jacobians
mjtNum DquatFD[9];
mjtNum DsFD[9];
mjtNum DvelFD[9];
mjtNum DhFD[3];
mjd_quatIntegrateFD(DquatFD, DsFD, DvelFD, DhFD, quat, vel, h, eps);
// expect numerical equality of un/scaled velocity derivatives
EXPECT_THAT(AsVector(DvelFD, 9), Pointwise(DoubleNear(eps), DsFD));
// expect numerical equality of analytic and FD derivatives
EXPECT_THAT(AsVector(DquatFD, 9), Pointwise(DoubleNear(eps), Dquat));
EXPECT_THAT(AsVector(DvelFD, 9), Pointwise(DoubleNear(eps), Dvel));
EXPECT_THAT(AsVector(DhFD, 3), Pointwise(DoubleNear(eps), Dh));
}
}
}
} // namespace
} // namespace mujoco
|