| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| |
|
| | |
| |
|
| | #include "src/engine/engine_util_solve.h" |
| |
|
| | #include <cstddef> |
| | #include <iostream> |
| | #include <random> |
| | #include <iomanip> |
| | #include <string> |
| |
|
| | #include <gmock/gmock.h> |
| | #include <gtest/gtest.h> |
| | #include <mujoco/mujoco.h> |
| | #include "src/engine/engine_util_blas.h" |
| | #include "src/engine/engine_util_misc.h" |
| | #include "test/fixture.h" |
| |
|
| | namespace mujoco { |
| | namespace { |
| |
|
| | using ::testing::DoubleEq; |
| | using ::testing::Pointwise; |
| | using ::testing::DoubleNear; |
| | using ::testing::ElementsAre; |
| | using ::std::string; |
| | using ::std::setw; |
| | using QCQP2Test = MujocoTest; |
| |
|
| | TEST_F(QCQP2Test, DegenerateAMatrix) { |
| | |
| | const mjtNum Ain[9] { 6, -15, 2, -5 }; |
| |
|
| | |
| | const mjtNum bin[3] { -12, 49 }; |
| | const mjtNum d[3] { 11, 31 }; |
| | const mjtNum r = 0.01; |
| |
|
| | |
| | mjtNum res[2] { 999, 999 }; |
| |
|
| | EXPECT_EQ(mju_QCQP2(res, Ain, bin, d, r), 0); |
| | EXPECT_EQ(res[0], 0); |
| | EXPECT_EQ(res[1], 0); |
| | } |
| |
|
| | using QCQP3Test = MujocoTest; |
| |
|
| | TEST_F(QCQP3Test, DegenerateAMatrix) { |
| | |
| | const mjtNum Ain[9] { 1, 4, -2, -3, -7, 5, 2, -9, 0 }; |
| |
|
| | |
| | const mjtNum bin[3] { -12, 49, 8 }; |
| | const mjtNum d[3] { 11, 31, -23 }; |
| | const mjtNum r = 0.1; |
| |
|
| | |
| | mjtNum res[3] { 999, 999, 999 }; |
| |
|
| | EXPECT_EQ(mju_QCQP3(res, Ain, bin, d, r), 0); |
| | EXPECT_EQ(res[0], 0); |
| | EXPECT_EQ(res[1], 0); |
| | EXPECT_EQ(res[2], 0); |
| | } |
| |
|
| | |
| |
|
| | using BoxQPTest = MujocoTest; |
| |
|
| | |
| | mjtNum objective(const mjtNum* x, const mjtNum* H, const mjtNum* g, int n) { |
| | return 0.5 * mju_mulVecMatVec(x, H, x, n) + mju_dot(x, g, n); |
| | } |
| |
|
| | |
| | bool isQPminimum(const mjtNum* res, const mjtNum* H, const mjtNum* g, int n, |
| | const mjtNum* lower, const mjtNum* upper) { |
| | static const mjtNum eps = 1e-4; |
| | bool is_minimum = true; |
| | mjtNum* res_nudge = (mjtNum*) mju_malloc(sizeof(mjtNum)*n); |
| |
|
| | |
| | mjtNum value = objective(res, H, g, n); |
| | mjtNum value_nudge; |
| |
|
| | |
| | mju_copy(res_nudge, res, n); |
| | for (int i=0; i < n; i++) { |
| | |
| | res_nudge[i] = res[i] - eps; |
| | if (lower) { |
| | res_nudge[i] = mju_max(lower[i], res_nudge[i]); |
| | } |
| | value_nudge = objective(res_nudge, H, g, n); |
| | if (value_nudge - value < 0) { |
| | is_minimum = false; |
| | break; |
| | } |
| |
|
| | |
| | res_nudge[i] = res[i] + eps; |
| | if (upper) { |
| | res_nudge[i] = mju_min(upper[i], res_nudge[i]); |
| | } |
| | value_nudge = objective(res_nudge, H, g, n); |
| | if (value_nudge - value < 0) { |
| | is_minimum = false; |
| | break; |
| | } |
| |
|
| | |
| | res_nudge[i] = res[i]; |
| | } |
| |
|
| | mju_free(res_nudge); |
| | return is_minimum; |
| | } |
| |
|
| | |
| | void randomBoxQP(int n, mjtNum* H, mjtNum* g, mjtNum* lower, mjtNum* upper, |
| | int seed) { |
| | |
| | std::mt19937_64 rng; |
| | rng.seed(seed); |
| | std::normal_distribution<double> dist(0, 1); |
| |
|
| | |
| | mjtNum* sqrtH = (mjtNum*) mju_malloc(sizeof(mjtNum)*n*n); |
| |
|
| | for (int i=0; i < n; i++) { |
| | g[i] = dist(rng); |
| | lower[i] = 5*dist(rng); |
| | upper[i] = 5*dist(rng); |
| |
|
| | |
| | if (lower[i] > upper[i]) { |
| | mjtNum tmp = upper[i]; |
| | upper[i] = lower[i]; |
| | lower[i] = tmp; |
| | } |
| |
|
| | |
| | for (int j=0; j < n; j++) { |
| | sqrtH[n*i+j] = dist(rng); |
| | } |
| | } |
| |
|
| | |
| | mju_mulMatTMat(H, sqrtH, sqrtH, n, n, n); |
| |
|
| | mju_free(sqrtH); |
| | } |
| |
|
| | |
| | TEST_F(BoxQPTest, UnboundedQP) { |
| | |
| | static const int n = 2; |
| | mjtNum H[n*n] = { |
| | 2, 0, |
| | 0, 2 |
| | }; |
| | mjtNum g[n] = {1, 3}; |
| | mjtNum res[n] = {0, 0}; |
| | mjtNum R[n*(n+7)]; |
| |
|
| | int nfree = mju_boxQP(res, R, nullptr, H, g, n, |
| | nullptr, nullptr); |
| |
|
| | |
| | EXPECT_EQ(nfree, 2); |
| | EXPECT_THAT(res[0], DoubleEq(-g[0]/H[0])); |
| | EXPECT_THAT(res[1], DoubleEq(-g[1]/H[3])); |
| |
|
| | |
| | EXPECT_TRUE(isQPminimum(res, H, g, n, nullptr, nullptr)); |
| |
|
| | |
| | res[0] += 0.001; |
| | EXPECT_FALSE(isQPminimum(res, H, g, n, nullptr, nullptr)); |
| |
|
| | |
| | H[0] = -1; |
| | nfree = mju_boxQP(res, R, nullptr, H, g, n, |
| | nullptr, nullptr); |
| |
|
| | EXPECT_EQ(nfree, -1); |
| | } |
| |
|
| | |
| | TEST_F(BoxQPTest, AsymmetricUpperIgnored) { |
| | |
| | static const int n = 2; |
| | mjtNum H[n*n] = { |
| | 1, -400, |
| | 0, 1 |
| | }; |
| | mjtNum g[n] = {1, 3}; |
| | mjtNum res[n] = {0, 0}; |
| | mjtNum lower[n] = {-2, -2}; |
| | mjtNum upper[n] = {0, 0}; |
| | int index[n]; |
| | mjtNum R[n*(n+7)]; |
| |
|
| | |
| | int nfree = mju_boxQP(res, R, index, H, g, n, lower, upper); |
| |
|
| | EXPECT_EQ(nfree, 1); |
| |
|
| | EXPECT_THAT(res[0], DoubleEq(-g[0]/H[0])); |
| | EXPECT_THAT(res[1], DoubleEq(lower[1])); |
| | } |
| |
|
| | |
| | TEST_F(BoxQPTest, BoundedQP) { |
| | int n = 50; |
| |
|
| | |
| | mjtNum *H, *g, *lower, *upper; |
| | mjtNum *res, *R; |
| | int* index; |
| | mju_boxQPmalloc(&res, &R, &index, &H, &g, n, &lower, &upper); |
| |
|
| | randomBoxQP(n, H, g, lower, upper, 1); |
| |
|
| | |
| | mju_zero(res, n); |
| |
|
| | |
| | int maxiter = 100; |
| | mjtNum mingrad = 1E-16; |
| | mjtNum backtrack = 0.5; |
| | mjtNum minstep = 1E-22; |
| | mjtNum armijo = 0.1; |
| |
|
| | |
| | static const int logsz = 10000; |
| | char log[logsz]; |
| |
|
| | int nfree = mju_boxQPoption(res, R, index, H, g, n, lower, upper, |
| | maxiter, mingrad, backtrack, |
| | minstep, armijo, log, logsz); |
| |
|
| | |
| |
|
| | |
| | EXPECT_GT(nfree, -1); |
| | EXPECT_TRUE(isQPminimum(res, H, g, n, lower, upper)); |
| |
|
| | |
| | int j = nfree > 0 ? 0 : -1; |
| | for (int i=0; i < n; i++) { |
| | if (j >= 0 && i == index[j]) { |
| | EXPECT_GT(res[i], lower[i]); |
| | EXPECT_LT(res[i], upper[i]); |
| | j++; |
| | } else { |
| | EXPECT_TRUE(res[i] == lower[i] || res[i] == upper[i]); |
| | } |
| | } |
| | mju_free(res); |
| | mju_free(R); |
| | mju_free(index); |
| | mju_free(H); |
| | mju_free(g); |
| | mju_free(lower); |
| | mju_free(upper); |
| | } |
| |
|
| | |
| | TEST_F(BoxQPTest, BoundedQPvariations) { |
| | int nmax = 100; |
| |
|
| | |
| | mjtNum *H, *g, *lower, *upper; |
| | mjtNum *res, *R; |
| | int* index; |
| | mju_boxQPmalloc(&res, &R, &index, &H, &g, nmax, &lower, &upper); |
| |
|
| | |
| | static const int logsz = 10000; |
| | char log[logsz]; |
| |
|
| | int seed = 1; |
| | for (int n : {3, 30, 100}) { |
| | int count = 0; |
| | int factorizations = 0; |
| | for (mjtNum scaleH : {.01, 1.0, 100.0}) { |
| | for (mjtNum scaleg : {.01, 1.0, 100.0}) { |
| | for (mjtNum scalebounds : {.01, 1.0, 100.0}) { |
| | |
| | randomBoxQP(n, H, g, lower, upper, seed++); |
| |
|
| | mju_scl(H, H, scaleH, n*n); |
| | mju_scl(g, g, scaleg, n); |
| | mju_scl(lower, lower, scalebounds, n); |
| | mju_scl(upper, upper, scalebounds, n); |
| |
|
| | |
| | mju_zero(res, n); |
| |
|
| | |
| | int maxiter = 100; |
| | mjtNum mingrad = 1E-16; |
| | mjtNum backtrack = 0.5; |
| | mjtNum minstep = 1E-22; |
| | mjtNum armijo = 0.1; |
| |
|
| | |
| | int nfree = mju_boxQPoption(res, R, index, H, g, n, lower, upper, |
| | maxiter, mingrad, backtrack, |
| | minstep, armijo, log, logsz); |
| |
|
| | |
| | EXPECT_GT(nfree, -1) << log; |
| | EXPECT_TRUE(isQPminimum(res, H, g, n, lower, upper)) |
| | << "n " << n << '\n' |
| | << "scaleH " << scaleH << '\n' |
| | << "scaleg " << scaleg << '\n' |
| | << "scalebounds " << scalebounds << '\n'; |
| |
|
| | |
| | string slog(log); |
| | string factorstr = "factorizations="; |
| | std::size_t index = slog.find(factorstr) + factorstr.length(); |
| | int num_factor = std::stoi(slog.substr(index, 3)); |
| |
|
| | |
| | EXPECT_LE(num_factor, 6); |
| |
|
| | factorizations += num_factor; |
| | count++; |
| | } |
| | } |
| | } |
| | double meanfactor = ((double)factorizations) / count; |
| |
|
| | |
| | EXPECT_LE(meanfactor, 5.0); |
| |
|
| | std::cerr << "n=" << setw(3) << n |
| | << ": average of " << meanfactor << " factorizations\n"; |
| | } |
| | mju_free(res); |
| | mju_free(R); |
| | mju_free(index); |
| | mju_free(H); |
| | mju_free(g); |
| | mju_free(lower); |
| | mju_free(upper); |
| | } |
| |
|
| | |
| |
|
| | using BandMatrixTest = MujocoTest; |
| |
|
| | |
| | |
| | void randomBanded(mjtNum* H, int nTotal, int nBand, int nDense, int seed, |
| | mjtNum* vec = nullptr, mjtNum reg = 0) { |
| | |
| | std::mt19937_64 rng; |
| | rng.seed(seed); |
| | std::normal_distribution<double> dist(0, 1); |
| |
|
| | |
| | mjtNum* sqrtH = (mjtNum*) mju_malloc(sizeof(mjtNum)*nTotal*nTotal); |
| |
|
| | |
| | for (int i=0; i < nTotal; i++) { |
| | if (vec) vec[i] = dist(rng); |
| | for (int j=0; j < nTotal; j++) { |
| | sqrtH[nTotal*i+j] = dist(rng); |
| | } |
| | } |
| |
|
| | |
| | mju_mulMatTMat(H, sqrtH, sqrtH, nTotal, nTotal, nTotal); |
| |
|
| | |
| | int nSparse = nTotal-nDense; |
| | for (int i=0; i < nSparse; i++) { |
| | int nzeros = mjMAX(0, i + 1 - nBand); |
| | for (int j=0; j < nzeros; j++) { |
| | H[nTotal*i + j] = 0; |
| | H[nTotal*j + i] = 0; |
| | } |
| | } |
| |
|
| | |
| | for (int i=0; i < nTotal; i++) { |
| | H[nTotal*i + i] += reg; |
| | } |
| |
|
| | mju_free(sqrtH); |
| | } |
| |
|
| |
|
| | |
| | TEST_F(BandMatrixTest, Diagonal) { |
| | int seed = 1; |
| | int nTotal = 8; |
| | for (int nBand : {1, 3}) { |
| | for (int nDense : {0, 2}) { |
| | |
| | int nB = (nTotal-nDense)*nBand + nDense*nTotal; |
| | mjtNum* B = (mjtNum*) mju_malloc(sizeof(mjtNum)*nB); |
| | int nH = nTotal*nTotal; |
| | mjtNum* H = (mjtNum*) mju_malloc(sizeof(mjtNum)*nH); |
| |
|
| | |
| | randomBanded(H, nTotal, nBand, nDense, seed++); |
| |
|
| | |
| | mju_dense2Band(B, H, nTotal, nBand, nDense); |
| |
|
| | |
| | for (int i=0; i < nTotal; i++) { |
| | EXPECT_EQ(H[i*nTotal + i], B[mju_bandDiag(i, nTotal, nBand, nDense)]); |
| | } |
| |
|
| | mju_free(H); |
| | mju_free(B); |
| | } |
| | } |
| | } |
| |
|
| | |
| | TEST_F(BandMatrixTest, Conversion) { |
| | int seed = 1; |
| | int nTotal = 8; |
| | for (int nBand : {0, 1, 3}) { |
| | for (int nDense : {0, 2}) { |
| | |
| | int nB = (nTotal-nDense)*nBand + nDense*nTotal; |
| | mjtNum* B = (mjtNum*) mju_malloc(sizeof(mjtNum)*nB); |
| | int nH = nTotal*nTotal; |
| | mjtNum* H = (mjtNum*) mju_malloc(sizeof(mjtNum)*nH); |
| | mjtNum* H1 = (mjtNum*) mju_malloc(sizeof(mjtNum)*nH); |
| |
|
| | |
| | randomBanded(H, nTotal, nBand, nDense, seed++); |
| |
|
| | |
| | mju_dense2Band(B, H, nTotal, nBand, nDense); |
| |
|
| | |
| | mju_band2Dense(H1, B, nTotal, nBand, nDense, 1); |
| |
|
| | |
| | EXPECT_EQ(AsVector(H, nH), AsVector(H1, nH)); |
| |
|
| | mju_free(H1); |
| | mju_free(H); |
| | mju_free(B); |
| | } |
| | } |
| | } |
| |
|
| | |
| | TEST_F(BandMatrixTest, Multiplication) { |
| | int seed = 1; |
| | int nTotal = 8; |
| | for (int nBand : {0, 1, 3}) { |
| | for (int nDense : {0, 2}) { |
| | |
| | int nB = (nTotal-nDense)*nBand + nDense*nTotal; |
| | mjtNum* B = (mjtNum*) mju_malloc(sizeof(mjtNum)*nB); |
| | int nH = nTotal*nTotal; |
| | mjtNum* H = (mjtNum*) mju_malloc(sizeof(mjtNum)*nH); |
| | mjtNum* vec = (mjtNum*) mju_malloc(sizeof(mjtNum)*nTotal); |
| | mjtNum* res = (mjtNum*) mju_malloc(sizeof(mjtNum)*nTotal); |
| | mjtNum* res1 = (mjtNum*) mju_malloc(sizeof(mjtNum)*nTotal); |
| |
|
| | |
| | randomBanded(H, nTotal, nBand, nDense, seed++, vec); |
| |
|
| | |
| | mju_mulMatVec(res, H, vec, nTotal, nTotal); |
| |
|
| | |
| | mju_dense2Band(B, H, nTotal, nBand, nDense); |
| | mju_bandMulMatVec(res1, B, vec, nTotal, nBand, nDense, |
| | 1, 1); |
| |
|
| | |
| | mjtNum eps = 1e-12; |
| | EXPECT_THAT(AsVector(res, nTotal), |
| | Pointwise(DoubleNear(eps), AsVector(res1, nTotal))); |
| |
|
| | mju_free(res1); |
| | mju_free(res); |
| | mju_free(vec); |
| | mju_free(H); |
| | mju_free(B); |
| | } |
| | } |
| | } |
| |
|
| | |
| | TEST_F(BandMatrixTest, Factorization) { |
| | int seed = 1; |
| | int nTotal = 8; |
| | for (int nBand : {1, 3}) { |
| | for (int nDense : {0, 2}) { |
| | for (mjtNum diagadd : {0.0, 1.0}) { |
| | for (int diagmul : {0.0, 1.3}) { |
| | |
| | int nB = (nTotal-nDense)*nBand + nDense*nTotal; |
| | mjtNum* B = (mjtNum*) mju_malloc(sizeof(mjtNum)*nB); |
| | int nH = nTotal*nTotal; |
| | mjtNum* H = (mjtNum*) mju_malloc(sizeof(mjtNum)*nH); |
| | mjtNum* H1 = (mjtNum*) mju_malloc(sizeof(mjtNum)*nH); |
| | mjtNum* vec = (mjtNum*) mju_malloc(sizeof(mjtNum)*nTotal); |
| | mjtNum* res = (mjtNum*) mju_malloc(sizeof(mjtNum)*nTotal); |
| | mjtNum* res1 = (mjtNum*) mju_malloc(sizeof(mjtNum)*nTotal); |
| |
|
| | |
| | |
| | randomBanded(H, nTotal, nBand, nDense, seed++, vec, nTotal); |
| |
|
| | |
| | mju_dense2Band(B, H, nTotal, nBand, nDense); |
| |
|
| | |
| | for (int i=0; i < nTotal; i++) { |
| | H[nTotal*i + i] += diagadd + diagmul*H[nTotal*i + i]; |
| | } |
| |
|
| | |
| | int rank = mju_cholFactor(H, nTotal, 0); |
| |
|
| | |
| | EXPECT_EQ(rank, nTotal); |
| |
|
| | |
| | mjtNum minDiag = mju_cholFactorBand(B, nTotal, nBand, nDense, |
| | diagadd, diagmul); |
| |
|
| | |
| | EXPECT_GT(minDiag, 0); |
| |
|
| | |
| | mju_band2Dense(H1, B, nTotal, nBand, nDense, 0); |
| |
|
| | |
| | for (int i=0; i < nTotal-1; i++) { |
| | mju_zero(H + nTotal*i + i + 1, nTotal - i - 1); |
| | } |
| |
|
| | |
| | mjtNum eps = 1e-12; |
| | EXPECT_THAT(AsVector(H, nH), |
| | Pointwise(DoubleNear(eps), AsVector(H1, nH))); |
| |
|
| | |
| | mju_mulMatVec(res, H, vec, nTotal, nTotal); |
| |
|
| | |
| | mju_bandMulMatVec(res1, B, vec, nTotal, nBand, nDense, |
| | 1, 0); |
| |
|
| | |
| | EXPECT_THAT(AsVector(res, nTotal), |
| | Pointwise(DoubleNear(eps), AsVector(res1, nTotal))); |
| |
|
| | mju_free(res1); |
| | mju_free(res); |
| | mju_free(vec); |
| | mju_free(H1); |
| | mju_free(H); |
| | mju_free(B); |
| | } |
| | } |
| | } |
| | } |
| | } |
| |
|
| | |
| | TEST_F(BandMatrixTest, Solve) { |
| | int seed = 1; |
| | int nTotal = 8; |
| | for (int nBand : {1, 3}) { |
| | for (int nDense : {0, 2}) { |
| | |
| | int nB = (nTotal-nDense)*nBand + nDense*nTotal; |
| | mjtNum* B = (mjtNum*) mju_malloc(sizeof(mjtNum)*nB); |
| | int nH = nTotal*nTotal; |
| | mjtNum* H = (mjtNum*) mju_malloc(sizeof(mjtNum)*nH); |
| | mjtNum* H1 = (mjtNum*) mju_malloc(sizeof(mjtNum)*nH); |
| | mjtNum* vec = (mjtNum*) mju_malloc(sizeof(mjtNum)*nTotal); |
| | mjtNum* res = (mjtNum*) mju_malloc(sizeof(mjtNum)*nTotal); |
| | mjtNum* res1 = (mjtNum*) mju_malloc(sizeof(mjtNum)*nTotal); |
| |
|
| | |
| | |
| | randomBanded(H, nTotal, nBand, nDense, seed++, vec, nTotal); |
| |
|
| | |
| | mju_dense2Band(B, H, nTotal, nBand, nDense); |
| |
|
| | |
| | int rank = mju_cholFactor(H, nTotal, 0); |
| |
|
| | |
| | EXPECT_EQ(rank, nTotal); |
| |
|
| | |
| | mjtNum minDiag = mju_cholFactorBand(B, nTotal, nBand, nDense, |
| | 0, 0); |
| |
|
| | |
| | EXPECT_GT(minDiag, 0); |
| |
|
| | |
| | mju_band2Dense(H1, B, nTotal, nBand, nDense, 0); |
| |
|
| | |
| | mju_cholSolve(res, H, vec, nTotal); |
| |
|
| | |
| | mju_cholSolveBand(res1, B, vec, nTotal, nBand, nDense); |
| |
|
| | |
| | mjtNum eps = 1e-12; |
| | EXPECT_THAT(AsVector(res, nTotal), |
| | Pointwise(DoubleNear(eps), AsVector(res1, nTotal))); |
| |
|
| | mju_free(res1); |
| | mju_free(res); |
| | mju_free(vec); |
| | mju_free(H1); |
| | mju_free(H); |
| | mju_free(B); |
| | } |
| | } |
| | } |
| |
|
| | using EngineUtilSolveTest = MujocoTest; |
| |
|
| | TEST_F(EngineUtilSolveTest, MjuCholFactorNNZ) { |
| | mjModel* model = LoadModelFromString("<mujoco/>"); |
| | mjData* d = mj_makeData(model); |
| |
|
| | int nA = 2; |
| | mjtNum matA[4] = {1, 0, |
| | 0, 1}; |
| | mjtNum sparseA[4]; |
| | int rownnzA[2]; |
| | int rowadrA[2]; |
| | int colindA[4]; |
| | int rownnzA_factor[2]; |
| | mju_dense2sparse(sparseA, matA, nA, nA, rownnzA, rowadrA, colindA, 4); |
| | int nnzA = mju_cholFactorCount(rownnzA_factor, |
| | rownnzA, rowadrA, colindA, nA, d); |
| |
|
| | EXPECT_EQ(nnzA, 2); |
| | EXPECT_THAT(AsVector(rownnzA_factor, 2), ElementsAre(1, 1)); |
| |
|
| | int nB = 3; |
| | mjtNum matB[9] = {10, 1, 0, |
| | 0, 10, 1, |
| | 0, 0, 10}; |
| | mjtNum sparseB[9]; |
| | int rownnzB[3]; |
| | int rowadrB[3]; |
| | int colindB[9]; |
| | int rownnzB_factor[3]; |
| | mju_dense2sparse(sparseB, matB, nB, nB, rownnzB, rowadrB, colindB, 9); |
| | int nnzB = mju_cholFactorCount(rownnzB_factor, |
| | rownnzB, rowadrB, colindB, nB, d); |
| |
|
| | EXPECT_EQ(nnzB, 5); |
| | EXPECT_THAT(AsVector(rownnzB_factor, 3), ElementsAre(1, 2, 2)); |
| |
|
| | int nC = 3; |
| | mjtNum matC[9] = {10, 1, 0, |
| | 0, 10, 0, |
| | 0, 0, 10}; |
| | mjtNum sparseC[9]; |
| | int rownnzC[3]; |
| | int rowadrC[3]; |
| | int colindC[9]; |
| | int rownnzC_factor[3]; |
| | mju_dense2sparse(sparseC, matC, nC, nC, rownnzC, rowadrC, colindC, 9); |
| | int nnzC = mju_cholFactorCount(rownnzC_factor, |
| | rownnzC, rowadrC, colindC, nC, d); |
| |
|
| | EXPECT_EQ(nnzC, 4); |
| | EXPECT_THAT(AsVector(rownnzC_factor, 3), ElementsAre(1, 2, 1)); |
| |
|
| | int nD = 4; |
| | mjtNum matD[16] = {10, 1, 2, 3, |
| | 0, 10, 0, 0, |
| | 0, 0, 10, 1, |
| | 0, 0, 0, 10}; |
| | mjtNum sparseD[16]; |
| | int rownnzD[4]; |
| | int rowadrD[4]; |
| | int colindD[16]; |
| | int rownnzD_factor[4]; |
| | mju_dense2sparse(sparseD, matD, nD, nD, rownnzD, rowadrD, colindD, 16); |
| | int nnzD = mju_cholFactorCount(rownnzD_factor, |
| | rownnzD, rowadrD, colindD, nD, d); |
| |
|
| | EXPECT_EQ(nnzD, 8); |
| | EXPECT_THAT(AsVector(rownnzD_factor, 4), ElementsAre(1, 2, 2, 3)); |
| |
|
| | mj_deleteData(d); |
| | mj_deleteModel(model); |
| | } |
| |
|
| | } |
| | } |
| |
|