| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| |
|
| | #include "engine/engine_solver.h" |
| |
|
| | #include <stddef.h> |
| | #include <string.h> |
| |
|
| | #include <mujoco/mjdata.h> |
| | #include <mujoco/mjmacro.h> |
| | #include <mujoco/mjmodel.h> |
| | #include <mujoco/mjsan.h> |
| | #include "engine/engine_core_constraint.h" |
| | #include "engine/engine_core_smooth.h" |
| | #include "engine/engine_io.h" |
| | #include "engine/engine_support.h" |
| | #include "engine/engine_util_blas.h" |
| | #include "engine/engine_util_errmem.h" |
| | #include "engine/engine_util_misc.h" |
| | #include "engine/engine_util_solve.h" |
| | #include "engine/engine_util_sparse.h" |
| |
|
| |
|
| | |
| |
|
| | |
| | static void saveStats(const mjModel* m, mjData* d, int island, int iter, |
| | mjtNum improvement, mjtNum gradient, mjtNum lineslope, |
| | int nactive, int nchange, int neval, int nupdate) { |
| | |
| | if (island >= mjNISLAND) { |
| | return; |
| | } |
| |
|
| | |
| | island = mjMAX(0, island); |
| |
|
| | |
| | if (iter >= mjNSOLVER) { |
| | return; |
| | } |
| |
|
| | |
| | mjSolverStat* stat = d->solver + island*mjNSOLVER + iter; |
| |
|
| | |
| | stat->improvement = improvement; |
| | stat->gradient = gradient; |
| | stat->lineslope = lineslope; |
| | stat->nactive = nactive; |
| | stat->nchange = nchange; |
| | stat->neval = neval; |
| | stat->nupdate = nupdate; |
| | } |
| |
|
| |
|
| |
|
| | |
| | |
| | static void dualFinish(const mjModel* m, mjData* d) { |
| | |
| | mj_mulJacTVec(m, d, d->qfrc_constraint, d->efc_force); |
| |
|
| | |
| | mj_solveM(m, d, d->qacc, d->qfrc_constraint, 1); |
| | mju_addTo(d->qacc, d->qacc_smooth, m->nv); |
| | } |
| |
|
| |
|
| |
|
| | |
| | |
| | static void ARdiaginv(const mjModel* m, const mjData* d, mjtNum* res, int flg_subR) { |
| | int nefc = d->nefc; |
| | const mjtNum *AR = d->efc_AR; |
| | const mjtNum *R = d->efc_R; |
| |
|
| | |
| | if (mj_isSparse(m)) { |
| | const int *rowadr = d->efc_AR_rowadr; |
| | const int *rownnz = d->efc_AR_rownnz; |
| | const int *colind = d->efc_AR_colind; |
| |
|
| | for (int i=0; i < nefc; i++) { |
| | int nnz = rownnz[i]; |
| | for (int j=0; j < nnz; j++) { |
| | int adr = rowadr[i] + j; |
| | if (i == colind[adr]) { |
| | res[i] = 1 / (flg_subR ? mju_max(mjMINVAL, AR[adr] - R[i]) : AR[adr]); |
| | break; |
| | } |
| | } |
| | } |
| | } |
| |
|
| | |
| | else { |
| | for (int i=0; i < nefc; i++) { |
| | int adr = i * (nefc + 1); |
| | res[i] = 1 / (flg_subR ? mju_max(mjMINVAL, AR[adr] - R[i]) : AR[adr]); |
| | } |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | |
| | static void extractBlock(const mjModel* m, const mjData* d, mjtNum* Ac, |
| | int start, int n, int flg_subR) { |
| | int nefc = d->nefc; |
| | const mjtNum *AR = d->efc_AR; |
| |
|
| | |
| | if (mj_isSparse(m)) { |
| | const int* rownnz = d->efc_AR_rownnz; |
| | const int* rowadr = d->efc_AR_rowadr; |
| | const int* colind = d->efc_AR_colind; |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | int k; |
| | for (k=0; k < rownnz[start]; k++) { |
| | if (colind[rowadr[start]+k] == start) { |
| | break; |
| | } |
| | } |
| |
|
| | |
| | if (k >= rownnz[start]) { |
| | mjERROR("internal error"); |
| | } |
| |
|
| | |
| | for (int j=0; j < n; j++) { |
| | mju_copy(Ac+j*n, AR+rowadr[start+j]+k, n); |
| | } |
| | } |
| |
|
| | |
| | else { |
| | for (int j=0; j < n; j++) { |
| | mju_copy(Ac+j*n, AR+start+(start+j)*nefc, n); |
| | } |
| | } |
| |
|
| | |
| | if (flg_subR) { |
| | const mjtNum *R = d->efc_R; |
| | for (int j=0; j < n; j++) { |
| | Ac[j*(n+1)] -= R[start+j]; |
| | Ac[j*(n+1)] = mju_max(1e-10, Ac[j*(n+1)]); |
| | } |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | |
| | static void residual(const mjModel* m, const mjData* d, mjtNum* res, int i, int dim, int flg_subR) { |
| | int nefc = d->nefc; |
| |
|
| | |
| | if (mj_isSparse(m)) { |
| | for (int j=0; j < dim; j++) { |
| | res[j] = d->efc_b[i+j] + mju_dotSparse(d->efc_AR + d->efc_AR_rowadr[i+j], |
| | d->efc_force, |
| | d->efc_AR_rownnz[i+j], |
| | d->efc_AR_colind + d->efc_AR_rowadr[i+j]); |
| | } |
| | } |
| |
|
| | |
| | else { |
| | for (int j=0; j < dim; j++) { |
| | res[j] = d->efc_b[i+j] + mju_dot(d->efc_AR+(i+j)*nefc, d->efc_force, nefc); |
| | } |
| | } |
| |
|
| | if (flg_subR) { |
| | for (int j=0; j < dim; j++) { |
| | res[j] -= d->efc_R[i+j]*d->efc_force[i+j]; |
| | } |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | |
| | static mjtNum costChange(const mjtNum* A, mjtNum* force, const mjtNum* oldforce, |
| | const mjtNum* res, int dim) { |
| | mjtNum change; |
| |
|
| | |
| | if (dim == 1) { |
| | mjtNum delta = force[0] - oldforce[0]; |
| | change = 0.5*delta*delta*A[0] + delta*res[0]; |
| | } else { |
| | mjtNum delta[6]; |
| | mju_sub(delta, force, oldforce, dim); |
| | change = 0.5*mju_mulVecMatVec(delta, A, delta, dim) + mju_dot(delta, res, dim); |
| | } |
| |
|
| | |
| | if (change > 1e-10) { |
| | mju_copy(force, oldforce, dim); |
| | change = 0; |
| | } |
| |
|
| | return change; |
| | } |
| |
|
| |
|
| |
|
| | |
| | |
| | static int dualState(const mjModel* m, const mjData* d, int* state) { |
| | int ne = d->ne, nf = d->nf, nefc = d->nefc; |
| | const mjtNum* force = d->efc_force; |
| | const mjtNum* floss = d->efc_frictionloss; |
| |
|
| | |
| | int nactive = ne + nf; |
| |
|
| | |
| | for (int i=0; i < ne; i++) { |
| | state[i] = mjCNSTRSTATE_QUADRATIC; |
| | } |
| |
|
| | |
| | for (int i=ne; i < ne+nf; i++) { |
| | if (force[i] <= -floss[i]) { |
| | state[i] = mjCNSTRSTATE_LINEARPOS; |
| | } else if (force[i] >= floss[i]) { |
| | state[i] = mjCNSTRSTATE_LINEARNEG; |
| | } else { |
| | state[i] = mjCNSTRSTATE_QUADRATIC; |
| | } |
| | } |
| |
|
| | |
| | for (int i=ne+nf; i < nefc; i++) { |
| | |
| | if (d->efc_type[i] != mjCNSTR_CONTACT_ELLIPTIC) { |
| | if (force[i] <= 0) { |
| | state[i] = mjCNSTRSTATE_SATISFIED; |
| | } else { |
| | state[i] = mjCNSTRSTATE_QUADRATIC; |
| | nactive++; |
| | } |
| | } |
| |
|
| | |
| | else { |
| | |
| | mjContact* con = d->contact + d->efc_id[i]; |
| | int dim = con->dim, result = 0; |
| | mjtNum mu = con->mu, f[6]; |
| |
|
| | |
| | f[0] = force[i]/mu; |
| | for (int j=1; j < dim; j++) { |
| | f[j] = force[i+j]/con->friction[j-1]; |
| | } |
| |
|
| | |
| | mjtNum N = f[0]; |
| | mjtNum T = mju_norm(f+1, dim-1); |
| |
|
| | |
| | if (mu*N >= T) { |
| | result = mjCNSTRSTATE_SATISFIED; |
| | } |
| |
|
| | |
| | else if (N+mu*T <= 0) { |
| | result = mjCNSTRSTATE_QUADRATIC; |
| | nactive += dim; |
| | } |
| |
|
| | |
| | else { |
| | result = mjCNSTRSTATE_CONE; |
| | nactive += dim; |
| | } |
| |
|
| | |
| | for (int j=0; j < dim; j++) { |
| | state[i+j] = result; |
| | } |
| |
|
| | |
| | i += (dim-1); |
| | } |
| | } |
| |
|
| | return nactive; |
| | } |
| |
|
| |
|
| |
|
| | |
| |
|
| | |
| | void mj_solPGS(const mjModel* m, mjData* d, int maxiter) { |
| | int ne = d->ne, nf = d->nf, nefc = d->nefc; |
| | const mjtNum *floss = d->efc_frictionloss; |
| | mjtNum *force = d->efc_force; |
| | mj_markStack(d); |
| | mjtNum* ARinv = mjSTACKALLOC(d, nefc, mjtNum); |
| | int* oldstate = mjSTACKALLOC(d, nefc, int); |
| |
|
| | |
| | int island = 0; |
| | mjtNum scale = 1 / (m->stat.meaninertia * mjMAX(1, m->nv)); |
| |
|
| | |
| | ARdiaginv(m, d, ARinv, 0); |
| |
|
| | |
| | dualState(m, d, d->efc_state); |
| |
|
| | |
| | int iter = 0; |
| | while (iter < maxiter) { |
| | |
| | mjtNum improvement = 0; |
| |
|
| | |
| | for (int i=0; i < nefc; i++) { |
| | |
| | int dim; |
| | if (d->efc_type[i] == mjCNSTR_CONTACT_ELLIPTIC) { |
| | dim = d->contact[d->efc_id[i]].dim; |
| | } else { |
| | dim = 1; |
| | } |
| |
|
| | |
| | mjtNum res[6]; |
| | residual(m, d, res, i, dim, 0); |
| |
|
| | |
| | mjtNum oldforce[6]; |
| | mju_copy(oldforce, force+i, dim); |
| |
|
| | |
| | mjtNum Athis[36]; |
| |
|
| | |
| | if (d->efc_type[i] != mjCNSTR_CONTACT_ELLIPTIC) { |
| | |
| | force[i] -= res[0]*ARinv[i]; |
| |
|
| | |
| | if (i >= ne && i < ne+nf) { |
| | if (force[i] < -floss[i]) { |
| | force[i] = -floss[i]; |
| | } else if (force[i] > floss[i]) { |
| | force[i] = floss[i]; |
| | } |
| | } else if (i >= ne+nf) { |
| | if (force[i] < 0) { |
| | force[i] = 0; |
| | } |
| | } |
| | } |
| |
|
| | |
| | else { |
| | |
| | mjtNum *mu = d->contact[d->efc_id[i]].friction; |
| |
|
| | |
| |
|
| | |
| | extractBlock(m, d, Athis, i, dim, 0); |
| |
|
| | |
| | if (force[i] < mjMINVAL) { |
| | |
| | force[i] -= res[0]*ARinv[i]; |
| |
|
| | |
| | if (force[i] < 0) { |
| | force[i] = 0; |
| | } |
| |
|
| | |
| | mju_zero(force+i+1, dim-1); |
| | } |
| |
|
| | |
| | else { |
| | |
| | mjtNum v[6]; |
| | mju_copy(v, force+i, dim); |
| |
|
| | |
| | mjtNum v1[6]; |
| | mju_mulMatVec(v1, Athis, v, dim, dim); |
| | mjtNum denom = mju_dot(v, v1, dim); |
| |
|
| | |
| | if (denom >= mjMINVAL) { |
| | |
| | mjtNum x = -mju_dot(v, res, dim) / denom; |
| |
|
| | |
| | if (force[i]+x*v[0] < 0) { |
| | x = -v[0]/force[i]; |
| | } |
| |
|
| | |
| | for (int j=0; j < dim; j++) { |
| | force[i+j] += x*v[j]; |
| | } |
| | } |
| | } |
| |
|
| | |
| |
|
| | |
| | mjtNum bc[5], Ac[25]; |
| | mju_copy(bc, res+1, dim-1); |
| | for (int j=0; j < dim-1; j++) { |
| | mju_copy(Ac+j*(dim-1), Athis+(j+1)*dim+1, dim-1); |
| | bc[j] -= mju_dot(Ac+j*(dim-1), oldforce+1, dim-1); |
| | bc[j] += Athis[(j+1)*dim]*(force[i]-oldforce[0]); |
| | } |
| |
|
| | |
| | if (force[i] < mjMINVAL) { |
| | mju_zero(force+i+1, dim-1); |
| | } |
| |
|
| | |
| | else { |
| | int flg_active; |
| | mjtNum v[6]; |
| |
|
| | |
| | if (dim == 3) { |
| | flg_active = mju_QCQP2(v, Ac, bc, mu, force[i]); |
| | } else if (dim == 4) { |
| | flg_active = mju_QCQP3(v, Ac, bc, mu, force[i]); |
| | } else { |
| | flg_active = mju_QCQP(v, Ac, bc, mu, force[i], dim-1); |
| | } |
| |
|
| | |
| | if (flg_active) { |
| | mjtNum s = 0; |
| | for (int j=0; j < dim-1; j++) { |
| | s += v[j]*v[j] / (mu[j]*mu[j]); |
| | } |
| | s = mju_sqrt(force[i]*force[i] / mju_max(mjMINVAL, s)); |
| | for (int j=0; j < dim-1; j++) { |
| | v[j] *= s; |
| | } |
| | } |
| |
|
| | |
| | mju_copy(force+i+1, v, dim-1); |
| | } |
| | } |
| |
|
| | |
| | if (dim == 1) { |
| | Athis[0] = 1/ARinv[i]; |
| | } |
| | improvement -= costChange(Athis, force+i, oldforce, res, dim); |
| |
|
| | |
| | i += (dim-1); |
| | } |
| |
|
| | |
| | mju_copyInt(oldstate, d->efc_state, nefc); |
| | int nactive = dualState(m, d, d->efc_state); |
| | int nchange = 0; |
| | for (int i=0; i < nefc; i++) { |
| | nchange += (oldstate[i] != d->efc_state[i]); |
| | } |
| |
|
| | |
| | improvement *= scale; |
| | saveStats(m, d, island, iter, improvement, 0, 0, nactive, nchange, 0, 0); |
| |
|
| | |
| | iter++; |
| |
|
| |
|
| | |
| | if (improvement < m->opt.tolerance) { |
| | break; |
| | } |
| | } |
| |
|
| | |
| | if (island < mjNISLAND) { |
| | |
| | d->solver_niter[island] += iter; |
| |
|
| | |
| | if (mj_isSparse(m)) { |
| | d->solver_nnz[island] = 0; |
| | for (int i=0; i < nefc; i++) { |
| | d->solver_nnz[island] += d->efc_AR_rownnz[i]; |
| | } |
| | } else { |
| | d->solver_nnz[island] = nefc*nefc; |
| | } |
| | } |
| |
|
| | |
| | dualFinish(m, d); |
| |
|
| | mj_freeStack(d); |
| | } |
| |
|
| |
|
| |
|
| | |
| |
|
| | |
| | void mj_solNoSlip(const mjModel* m, mjData* d, int maxiter) { |
| | int dim, iter = 0, ne = d->ne, nf = d->nf, nefc = d->nefc; |
| | const mjtNum *floss = d->efc_frictionloss; |
| | mjtNum *force = d->efc_force; |
| | mjtNum *mu, improvement; |
| | mjtNum v[5], Ac[25], bc[5], res[5], oldforce[5], delta[5], mid, y, K0, K1; |
| | mjContact* con; |
| | mj_markStack(d); |
| | mjtNum* ARinv = mjSTACKALLOC(d, nefc, mjtNum); |
| | int* oldstate = mjSTACKALLOC(d, nefc, int); |
| |
|
| | |
| | int island = 0; |
| | mjtNum scale = 1 / (m->stat.meaninertia * mjMAX(1, m->nv)); |
| |
|
| | |
| | ARdiaginv(m, d, ARinv, 1); |
| |
|
| | |
| | dualState(m, d, d->efc_state); |
| |
|
| | |
| | while (iter < maxiter) { |
| | |
| | improvement = 0; |
| |
|
| | |
| | if (iter == 0) { |
| | for (int i=0; i < nefc; i++) { |
| | improvement += 0.5*force[i]*force[i]*d->efc_R[i]; |
| | } |
| | } |
| |
|
| | |
| | for (int i=ne; i < ne+nf; i++) { |
| | |
| | residual(m, d, res, i, 1, 1); |
| | oldforce[0] = force[i]; |
| |
|
| | |
| | force[i] -= res[0]*ARinv[i]; |
| |
|
| | |
| | if (force[i] < -floss[i]) { |
| | force[i] = -floss[i]; |
| | } else if (force[i] > floss[i]) { |
| | force[i] = floss[i]; |
| | } |
| |
|
| | |
| | delta[0] = force[i] - oldforce[0]; |
| | improvement -= 0.5*delta[0]*delta[0]/ARinv[i] + delta[0]*res[0]; |
| | } |
| |
|
| | |
| | for (int i=ne+nf; i < nefc; i++) { |
| | |
| | if (d->efc_type[i] == mjCNSTR_CONTACT_PYRAMIDAL) { |
| | |
| | con = d->contact + d->efc_id[i]; |
| | dim = con->dim; |
| | mu = con->friction; |
| |
|
| | |
| | for (int j=i; j < i+2*(dim-1); j+=2) { |
| | |
| | residual(m, d, res, j, 2, 1); |
| | mju_copy(oldforce, force+j, 2); |
| |
|
| | |
| | extractBlock(m, d, Ac, j, 2, 1); |
| |
|
| | |
| | mju_copy(bc, res, 2); |
| | for (int k=0; k < 2; k++) { |
| | bc[k] -= mju_dot(Ac+k*2, oldforce, 2); |
| | } |
| |
|
| | |
| | mid = 0.5*(force[j]+force[j+1]); |
| | y = 0.5*(force[j]-force[j+1]); |
| |
|
| | |
| | K1 = Ac[0] + Ac[3] - Ac[1] - Ac[2]; |
| | K0 = mid*(Ac[0] - Ac[3]) + bc[0] - bc[1]; |
| |
|
| | |
| | if (K1 < mjMINVAL) { |
| | force[j] = force[j+1] = mid; |
| | } |
| |
|
| | |
| | else { |
| | |
| | y = -K0/K1; |
| |
|
| | |
| | if (y < -mid) { |
| | force[j] = 0; |
| | force[j+1] = 2*mid; |
| | } else if (y > mid) { |
| | force[j] = 2*mid; |
| | force[j+1] = 0; |
| | } else { |
| | force[j] = mid+y; |
| | force[j+1] = mid-y; |
| | } |
| | } |
| |
|
| | |
| | improvement -= costChange(Ac, force+j, oldforce, res, 2); |
| | } |
| |
|
| | |
| | i += 2*(dim-1)-1; |
| | } |
| |
|
| | |
| | else if (d->efc_type[i] == mjCNSTR_CONTACT_ELLIPTIC) { |
| | |
| | con = d->contact + d->efc_id[i]; |
| | dim = con->dim; |
| | mu = con->friction; |
| |
|
| | |
| | residual(m, d, res, i+1, dim-1, 1); |
| | mju_copy(oldforce, force+i+1, dim-1); |
| |
|
| | |
| | extractBlock(m, d, Ac, i+1, dim-1, 1); |
| |
|
| | |
| | mju_copy(bc, res, dim-1); |
| | for (int j=0; j < dim-1; j++) { |
| | bc[j] -= mju_dot(Ac+j*(dim-1), oldforce, dim-1); |
| | } |
| |
|
| | |
| | if (force[i] < mjMINVAL) { |
| | mju_zero(force+i+1, dim-1); |
| | } |
| |
|
| | |
| | else { |
| | int flg_active = 0; |
| |
|
| | |
| | if (dim == 3) { |
| | flg_active = mju_QCQP2(v, Ac, bc, mu, force[i]); |
| | } else if (dim == 4) { |
| | flg_active = mju_QCQP3(v, Ac, bc, mu, force[i]); |
| | } else { |
| | flg_active = mju_QCQP(v, Ac, bc, mu, force[i], dim-1); |
| | } |
| |
|
| | |
| | if (flg_active) { |
| | mjtNum s = 0; |
| | for (int j=0; j < dim-1; j++) { |
| | s += v[j]*v[j]/(mu[j]*mu[j]); |
| | } |
| | s = mju_sqrt(force[i]*force[i] / mju_max(mjMINVAL, s)); |
| | for (int j=0; j < dim-1; j++) { |
| | v[j] *= s; |
| | } |
| | } |
| |
|
| | |
| | mju_copy(force+i+1, v, dim-1); |
| | } |
| |
|
| | |
| | improvement -= costChange(Ac, force+i+1, oldforce, res, dim-1); |
| |
|
| | |
| | i += (dim-1); |
| | } |
| | } |
| |
|
| | |
| | mju_copyInt(oldstate, d->efc_state, nefc); |
| | int nactive = dualState(m, d, d->efc_state); |
| | int nchange = 0; |
| | for (int i=0; i < nefc; i++) { |
| | nchange += (oldstate[i] != d->efc_state[i]); |
| | } |
| |
|
| | |
| | improvement *= scale; |
| |
|
| | |
| | int stats_iter = iter + d->solver_niter[island]; |
| | saveStats(m, d, island, stats_iter, improvement, 0, 0, nactive, nchange, 0, 0); |
| |
|
| | |
| | iter++; |
| |
|
| | |
| | if (improvement < m->opt.noslip_tolerance) { |
| | break; |
| | } |
| | } |
| |
|
| | |
| | d->solver_niter[island] += iter; |
| |
|
| | |
| | dualFinish(m, d); |
| |
|
| | mj_freeStack(d); |
| | } |
| |
|
| |
|
| |
|
| | |
| |
|
| | |
| | struct _mjCGContext { |
| | int is_sparse; |
| | int is_elliptic; |
| | int island; |
| |
|
| | |
| | int nv; |
| | int ne; |
| | int nf; |
| | int nefc; |
| |
|
| | |
| | mjContact* contact; |
| |
|
| | |
| | const mjtNum* qfrc_smooth; |
| | const mjtNum* qacc_smooth; |
| | mjtNum* qfrc_constraint; |
| | mjtNum* qacc; |
| |
|
| | |
| | const int* M_rownnz; |
| | const int* M_rowadr; |
| | const int* M_colind; |
| | const mjtNum* M; |
| | const mjtNum* qLD; |
| | const mjtNum* qLDiagInv; |
| |
|
| | |
| | const mjtNum* efc_D; |
| | const mjtNum* efc_R; |
| | const mjtNum* efc_frictionloss; |
| | const mjtNum* efc_aref; |
| | const int* efc_id; |
| | const int* efc_type; |
| | mjtNum* efc_force; |
| | int* efc_state; |
| |
|
| | |
| | const int* J_rownnz; |
| | const int* J_rowadr; |
| | const int* J_rowsuper; |
| | const int* J_colind; |
| | const int* JT_rownnz; |
| | const int* JT_rowadr; |
| | const int* JT_rowsuper; |
| | const int* JT_colind; |
| | const mjtNum* J; |
| | const mjtNum* JT; |
| |
|
| | |
| | mjtNum* Jaref; |
| | mjtNum* Jv; |
| | mjtNum* Ma; |
| | mjtNum* Mv; |
| | mjtNum* grad; |
| | mjtNum* Mgrad; |
| | mjtNum* search; |
| | mjtNum* quad; |
| |
|
| | |
| | mjtNum* D; |
| | int* H_rowadr; |
| | int* H_rownnz; |
| | int* H_lowernnz; |
| | int* L_rownnz; |
| | int* L_rowadr; |
| | int* buf_ind; |
| | mjtNum* buf_val; |
| |
|
| | |
| | int nH; |
| | int* H_colind; |
| | mjtNum* H; |
| | int nL; |
| | int* L_colind; |
| | mjtNum* L; |
| | mjtNum* Lcone; |
| |
|
| | |
| | mjtNum cost; |
| | mjtNum quadGauss[3]; |
| | mjtNum scale; |
| | int nactive; |
| | int ncone; |
| | int nupdate; |
| |
|
| | |
| | int LSiter; |
| | int LSresult; |
| | mjtNum LSslope; |
| | }; |
| | typedef struct _mjCGContext mjCGContext; |
| |
|
| |
|
| |
|
| | |
| | static void CGpointers(const mjModel* m, const mjData* d, mjCGContext* ctx, int island) { |
| | |
| | memset(ctx, 0, sizeof(mjCGContext)); |
| |
|
| | |
| | ctx->is_sparse = mj_isSparse(m); |
| | ctx->is_elliptic = (m->opt.cone == mjCONE_ELLIPTIC); |
| | ctx->contact = d->contact; |
| | ctx->island = island; |
| |
|
| | |
| | if (island < 0) { |
| | |
| | ctx->nv = m->nv; |
| | ctx->ne = d->ne; |
| | ctx->nf = d->nf; |
| | ctx->nefc = d->nefc; |
| |
|
| | |
| | ctx->qfrc_smooth = d->qfrc_smooth; |
| | ctx->qfrc_constraint = d->qfrc_constraint; |
| | ctx->qacc_smooth = d->qacc_smooth; |
| | ctx->qacc = d->qacc; |
| |
|
| | |
| | ctx->M_rownnz = d->M_rownnz; |
| | ctx->M_rowadr = d->M_rowadr; |
| | ctx->M_colind = d->M_colind; |
| | ctx->M = d->M; |
| | ctx->qLD = d->qLD; |
| | ctx->qLDiagInv = d->qLDiagInv; |
| |
|
| | |
| | ctx->efc_D = d->efc_D; |
| | ctx->efc_R = d->efc_R; |
| | ctx->efc_frictionloss = d->efc_frictionloss; |
| | ctx->efc_aref = d->efc_aref; |
| | ctx->efc_id = d->efc_id; |
| | ctx->efc_type = d->efc_type; |
| | ctx->efc_force = d->efc_force; |
| | ctx->efc_state = d->efc_state; |
| |
|
| | |
| | ctx->J = d->efc_J; |
| | if (ctx->is_sparse) { |
| | ctx->J_rownnz = d->efc_J_rownnz; |
| | ctx->J_rowadr = d->efc_J_rowadr; |
| | ctx->J_rowsuper = d->efc_J_rowsuper; |
| | ctx->J_colind = d->efc_J_colind; |
| | ctx->JT_rownnz = d->efc_JT_rownnz; |
| | ctx->JT_rowadr = d->efc_JT_rowadr; |
| | ctx->JT_rowsuper = d->efc_JT_rowsuper; |
| | ctx->JT_colind = d->efc_JT_colind; |
| | ctx->JT = d->efc_JT; |
| | } |
| | } |
| |
|
| | |
| | else { |
| | |
| | ctx->nv = d->island_nv[island]; |
| | ctx->ne = d->island_ne[island]; |
| | ctx->nf = d->island_nf[island]; |
| | ctx->nefc = d->island_nefc[island]; |
| |
|
| | |
| | int idofadr = d->island_idofadr[island]; |
| | ctx->qfrc_smooth = d->ifrc_smooth + idofadr; |
| | ctx->qfrc_constraint = d->ifrc_constraint + idofadr; |
| | ctx->qacc_smooth = d->iacc_smooth + idofadr; |
| | ctx->qacc = d->iacc + idofadr; |
| |
|
| | |
| | ctx->M_rownnz = d->iM_rownnz + idofadr; |
| | ctx->M_rowadr = d->iM_rowadr + idofadr; |
| | ctx->M_colind = d->iM_colind; |
| | ctx->M = d->iM; |
| | ctx->qLD = d->iLD; |
| | ctx->qLDiagInv = d->iLDiagInv + idofadr; |
| |
|
| | |
| | int iefcadr = d->island_iefcadr[island]; |
| | ctx->efc_D = d->iefc_D + iefcadr; |
| | ctx->efc_R = d->iefc_R + iefcadr; |
| | ctx->efc_frictionloss = d->iefc_frictionloss + iefcadr; |
| | ctx->efc_aref = d->iefc_aref + iefcadr; |
| | ctx->efc_id = d->iefc_id + iefcadr; |
| | ctx->efc_type = d->iefc_type + iefcadr; |
| | ctx->efc_force = d->iefc_force + iefcadr; |
| | ctx->efc_state = d->iefc_state + iefcadr; |
| |
|
| | |
| | if (!ctx->is_sparse) { |
| | ctx->J = d->iefc_J + d->nidof * iefcadr; |
| | } else { |
| | ctx->J_rownnz = d->iefc_J_rownnz + iefcadr; |
| | ctx->J_rowadr = d->iefc_J_rowadr + iefcadr; |
| | ctx->J_rowsuper = d->iefc_J_rowsuper + iefcadr; |
| | ctx->J_colind = d->iefc_J_colind; |
| | ctx->JT_rownnz = d->iefc_JT_rownnz + idofadr; |
| | ctx->JT_rowadr = d->iefc_JT_rowadr + idofadr; |
| | ctx->JT_rowsuper = d->iefc_JT_rowsuper + idofadr; |
| | ctx->JT_colind = d->iefc_JT_colind; |
| | ctx->J = d->iefc_J; |
| | ctx->JT = d->iefc_JT; |
| | } |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | |
| | static void CGallocate(mjData* d, mjCGContext* ctx, int flg_Newton) { |
| | |
| | int nv = ctx->nv; |
| | int nefc = ctx->nefc; |
| |
|
| | |
| | ctx->Jaref = mjSTACKALLOC(d, nefc, mjtNum); |
| | ctx->Jv = mjSTACKALLOC(d, nefc, mjtNum); |
| | ctx->Ma = mjSTACKALLOC(d, nv, mjtNum); |
| | ctx->Mv = mjSTACKALLOC(d, nv, mjtNum); |
| | ctx->grad = mjSTACKALLOC(d, nv, mjtNum); |
| | ctx->Mgrad = mjSTACKALLOC(d, nv, mjtNum); |
| | ctx->search = mjSTACKALLOC(d, nv, mjtNum); |
| | ctx->quad = mjSTACKALLOC(d, nefc*3, mjtNum); |
| |
|
| | |
| | if (flg_Newton) { |
| | ctx->D = mjSTACKALLOC(d, nefc, mjtNum); |
| |
|
| | |
| | if (ctx->is_sparse) { |
| | ctx->H_rowadr = mjSTACKALLOC(d, nv, int); |
| | ctx->H_rownnz = mjSTACKALLOC(d, nv, int); |
| | ctx->H_lowernnz = mjSTACKALLOC(d, nv, int); |
| | ctx->L_rownnz = mjSTACKALLOC(d, nv, int); |
| | ctx->L_rowadr = mjSTACKALLOC(d, nv, int); |
| | ctx->buf_val = mjSTACKALLOC(d, nv, mjtNum); |
| | ctx->buf_ind = mjSTACKALLOC(d, nv, int); |
| | } |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | static void CGupdateConstraint(mjCGContext* ctx, int flg_HessianCone) { |
| | int nefc = ctx->nefc, nv = ctx->nv; |
| |
|
| | |
| | mj_constraintUpdate_impl(ctx->ne, ctx->nf, ctx->nefc, ctx->efc_D, ctx->efc_R, |
| | ctx->efc_frictionloss, ctx->Jaref, ctx->efc_type, ctx->efc_id, |
| | ctx->contact, ctx->efc_state, ctx->efc_force, |
| | &(ctx->cost), flg_HessianCone); |
| |
|
| | |
| | if (!ctx->is_sparse) { |
| | mju_mulMatTVec(ctx->qfrc_constraint, ctx->J, ctx->efc_force, nefc, nv); |
| | } else { |
| | mju_mulMatVecSparse(ctx->qfrc_constraint, ctx->JT, ctx->efc_force, nv, |
| | ctx->JT_rownnz, ctx->JT_rowadr, ctx->JT_colind, ctx->JT_rowsuper); |
| | } |
| |
|
| | |
| | ctx->nactive = 0; |
| | ctx->ncone = 0; |
| | for (int i=0; i < nefc; i++) { |
| | ctx->nactive += (ctx->efc_state[i] != mjCNSTRSTATE_SATISFIED); |
| | ctx->ncone += (ctx->efc_state[i] == mjCNSTRSTATE_CONE); |
| | } |
| |
|
| | |
| | mjtNum Gauss = 0; |
| | for (int i=0; i < nv; i++) { |
| | Gauss += 0.5 * (ctx->Ma[i] - ctx->qfrc_smooth[i]) * (ctx->qacc[i] - ctx->qacc_smooth[i]); |
| | } |
| |
|
| | ctx->quadGauss[0] = Gauss; |
| | ctx->cost += Gauss; |
| | } |
| |
|
| |
|
| |
|
| | |
| | static void CGupdateGradient(mjCGContext* ctx, int flg_Newton) { |
| | int nv = ctx->nv; |
| |
|
| | |
| | for (int i=0; i < nv; i++) { |
| | ctx->grad[i] = ctx->Ma[i] - ctx->qfrc_smooth[i] - ctx->qfrc_constraint[i]; |
| | } |
| |
|
| | |
| | if (flg_Newton) { |
| | if (ctx->is_sparse) { |
| | mju_cholSolveSparse(ctx->Mgrad, (ctx->ncone ? ctx->Lcone : ctx->L), |
| | ctx->grad, nv, ctx->L_rownnz, ctx->L_rowadr, ctx->L_colind); |
| | } else { |
| | mju_cholSolve(ctx->Mgrad, (ctx->ncone ? ctx->Lcone : ctx->L), ctx->grad, nv); |
| | } |
| | } |
| |
|
| | |
| | else { |
| | mju_copy(ctx->Mgrad, ctx->grad, nv); |
| | mj_solveLD(ctx->Mgrad, ctx->qLD, ctx->qLDiagInv, nv, 1, |
| | ctx->M_rownnz, ctx->M_rowadr, ctx->M_colind); |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | static void CGprepare(mjCGContext* ctx) { |
| | int nv = ctx->nv, nefc = ctx->nefc; |
| | const mjtNum* v = ctx->search; |
| |
|
| | |
| | |
| | ctx->quadGauss[1] = mju_dot(v, ctx->Ma, nv) - mju_dot(ctx->qfrc_smooth, v, nv); |
| | ctx->quadGauss[2] = 0.5*mju_dot(v, ctx->Mv, nv); |
| |
|
| | |
| | for (int i=0; i < nefc; i++) { |
| | |
| | const mjtNum* Jv = ctx->Jv + i; |
| | const mjtNum* Jaref = ctx->Jaref + i; |
| | const mjtNum* D = ctx->efc_D + i; |
| |
|
| | |
| | mjtNum* quad = ctx->quad + 3*i; |
| |
|
| | |
| | mjtNum DJ0 = D[0]*Jaref[0]; |
| | quad[0] = Jaref[0]*DJ0; |
| | quad[1] = Jv[0]*DJ0; |
| | quad[2] = Jv[0]*D[0]*Jv[0]; |
| |
|
| | |
| | if (ctx->efc_type[i] == mjCNSTR_CONTACT_ELLIPTIC) { |
| | |
| | const mjContact* con = ctx->contact + ctx->efc_id[i]; |
| | int dim = con->dim; |
| | mjtNum U[6], V[6], UU = 0, UV = 0, VV = 0, mu = con->mu; |
| | const mjtNum* friction = con->friction; |
| |
|
| | |
| | for (int j=1; j < dim; j++) { |
| | mjtNum DJj = D[j]*Jaref[j]; |
| | quad[0] += Jaref[j]*DJj; |
| | quad[1] += Jv[j]*DJj; |
| | quad[2] += Jv[j]*D[j]*Jv[j]; |
| | } |
| |
|
| | |
| | U[0] = Jaref[0]*mu; |
| | V[0] = Jv[0]*mu; |
| | for (int j=1; j < dim; j++) { |
| | U[j] = Jaref[j]*friction[j-1]; |
| | V[j] = Jv[j]*friction[j-1]; |
| | } |
| |
|
| | |
| | for (int j=1; j < dim; j++) { |
| | UU += U[j]*U[j]; |
| | UV += U[j]*V[j]; |
| | VV += V[j]*V[j]; |
| | } |
| |
|
| | |
| | quad[3] = U[0]; |
| | quad[4] = V[0]; |
| | quad[5] = UU; |
| | quad[6] = UV; |
| | quad[7] = VV; |
| | quad[8] = D[0] / ((mu*mu) * (1 + (mu*mu))); |
| |
|
| | |
| | i += (dim-1); |
| | } |
| |
|
| | |
| | quad[0] *= 0.5; |
| | quad[2] *= 0.5; |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | struct _mjCGPnt { |
| | mjtNum alpha; |
| | mjtNum cost; |
| | mjtNum deriv[2]; |
| | }; |
| | typedef struct _mjCGPnt mjCGPnt; |
| |
|
| |
|
| |
|
| | |
| | static void CGeval(mjCGContext* ctx, mjCGPnt* p) { |
| | int ne = ctx->ne, nf = ctx->nf, nefc = ctx->nefc; |
| |
|
| | |
| | mjtNum cost = 0, alpha = p->alpha; |
| | mjtNum deriv[2] = {0, 0}; |
| |
|
| | |
| | mjtNum quadTotal[3]; |
| | mju_copy3(quadTotal, ctx->quadGauss); |
| |
|
| | |
| | for (int i=0; i < nefc; i++) { |
| | |
| | if (i < ne) { |
| | mju_addTo3(quadTotal, ctx->quad+3*i); |
| | continue; |
| | } |
| |
|
| | |
| | if (i < ne + nf) { |
| | |
| | mjtNum start = ctx->Jaref[i], dir = ctx->Jv[i]; |
| | mjtNum x = start + alpha*dir; |
| | mjtNum f = ctx->efc_frictionloss[i]; |
| | mjtNum Rf = ctx->efc_R[i]*f; |
| |
|
| | |
| | if (-Rf < x && x < Rf) { |
| | mju_addTo3(quadTotal, ctx->quad+3*i); |
| | } |
| |
|
| | |
| | else if (x <= -Rf) { |
| | mjtNum qf[3] = {f*(-0.5*Rf-start), -f*dir, 0}; |
| | mju_addTo3(quadTotal, qf); |
| | } |
| |
|
| | |
| | else { |
| | mjtNum qf[3] = {f*(-0.5*Rf+start), f*dir, 0}; |
| | mju_addTo3(quadTotal, qf); |
| | } |
| | continue; |
| | } |
| |
|
| | |
| | if (ctx->efc_type[i] == mjCNSTR_CONTACT_ELLIPTIC) { |
| | |
| | const mjContact* con = ctx->contact + ctx->efc_id[i]; |
| | mjtNum* quad = ctx->quad + 3*i; |
| | int dim = con->dim; |
| | mjtNum mu = con->mu; |
| |
|
| | |
| | mjtNum U0 = quad[3]; |
| | mjtNum V0 = quad[4]; |
| | mjtNum UU = quad[5]; |
| | mjtNum UV = quad[6]; |
| | mjtNum VV = quad[7]; |
| | mjtNum Dm = quad[8]; |
| |
|
| | |
| | mjtNum N = U0 + alpha*V0; |
| | mjtNum Tsqr = UU + alpha*(2*UV + alpha*VV); |
| |
|
| | |
| | if (Tsqr <= 0) { |
| | |
| | if (N < 0) { |
| | mju_addTo3(quadTotal, quad); |
| | } |
| |
|
| | |
| | } |
| |
|
| | |
| | else { |
| | |
| | mjtNum T = mju_sqrt(Tsqr); |
| |
|
| | |
| | if (N >= mu*T) { |
| | |
| | } |
| |
|
| | |
| | else if (mu*N+T <= 0) { |
| | mju_addTo3(quadTotal, quad); |
| | } |
| |
|
| | |
| | else { |
| | |
| | mjtNum N1 = V0; |
| | mjtNum T1 = (UV + alpha*VV)/T; |
| | mjtNum T2 = VV/T - (UV + alpha*VV)*T1/(T*T); |
| |
|
| | |
| | cost += 0.5*Dm*(N-mu*T)*(N-mu*T); |
| | deriv[0] += Dm*(N-mu*T)*(N1-mu*T1); |
| | deriv[1] += Dm*((N1-mu*T1)*(N1-mu*T1) + (N-mu*T)*(-mu*T2)); |
| | } |
| | } |
| |
|
| | |
| | i += (dim-1); |
| | } else { |
| | |
| | mjtNum x = ctx->Jaref[i] + alpha*ctx->Jv[i]; |
| |
|
| | |
| | if (x < 0) { |
| | mju_addTo3(quadTotal, ctx->quad+3*i); |
| | } |
| | } |
| | } |
| |
|
| | |
| | cost += alpha*alpha*quadTotal[2] + alpha*quadTotal[1] + quadTotal[0]; |
| | deriv[0] += 2*alpha*quadTotal[2] + quadTotal[1]; |
| | deriv[1] += 2*quadTotal[2]; |
| |
|
| | |
| | if (deriv[1] <= 0) { |
| | mju_warning("Linesearch objective is not convex"); |
| | deriv[1] = mjMINVAL; |
| | } |
| |
|
| | |
| | p->cost = cost; |
| | p->deriv[0] = deriv[0]; |
| | p->deriv[1] = deriv[1]; |
| | ctx->LSiter++; |
| | } |
| |
|
| |
|
| |
|
| | |
| | static int updateBracket(mjCGContext* ctx, |
| | mjCGPnt* p, const mjCGPnt candidates[3], mjCGPnt* pnext) { |
| | int flag = 0; |
| | for (int i=0; i < 3; i++) { |
| | |
| | if (p->deriv[0] < 0 && candidates[i].deriv[0] < 0 && p->deriv[0] < candidates[i].deriv[0]) { |
| | *p = candidates[i]; |
| | flag = 1; |
| | } |
| |
|
| | |
| | else if (p->deriv[0] > 0 && |
| | candidates[i].deriv[0] > 0 && |
| | p->deriv[0] > candidates[i].deriv[0]) { |
| | *p = candidates[i]; |
| | flag = 2; |
| | } |
| | } |
| |
|
| | |
| | if (flag) { |
| | pnext->alpha = p->alpha - p->deriv[0]/p->deriv[1]; |
| | CGeval(ctx, pnext); |
| | } |
| |
|
| | return flag; |
| | } |
| |
|
| |
|
| |
|
| | |
| | static mjtNum CGsearch(mjCGContext* ctx, mjtNum tolerance, mjtNum ls_iterations) { |
| | int nv = ctx->nv, nefc = ctx->nefc; |
| | mjCGPnt p0, p1, p2, pmid, p1next, p2next; |
| |
|
| | |
| | ctx->LSiter = 0; |
| | ctx->LSresult = 0; |
| | ctx->LSslope = 1; |
| |
|
| | |
| | mjtNum snorm = mju_norm(ctx->search, nv); |
| | if (snorm < mjMINVAL) { |
| | ctx->LSresult = 1; |
| | return 0; |
| | } |
| |
|
| | |
| | mjtNum gtol = tolerance * snorm / ctx->scale; |
| | mjtNum slopescl = ctx->scale / snorm; |
| |
|
| | |
| | mju_mulSymVecSparse(ctx->Mv, ctx->M, ctx->search, nv, |
| | ctx->M_rownnz, ctx->M_rowadr, ctx->M_colind); |
| |
|
| | |
| | if (!ctx->is_sparse) { |
| | mju_mulMatVec(ctx->Jv, ctx->J, ctx->search, nefc, nv); |
| | } else { |
| | mju_mulMatVecSparse(ctx->Jv, ctx->J, ctx->search, nefc, |
| | ctx->J_rownnz, ctx->J_rowadr, ctx->J_colind, ctx->J_rowsuper); |
| | } |
| |
|
| | |
| | CGprepare(ctx); |
| |
|
| | |
| | p0.alpha = 0; |
| | CGeval(ctx, &p0); |
| |
|
| | |
| | p1.alpha = p0.alpha - p0.deriv[0]/p0.deriv[1]; |
| | CGeval(ctx, &p1); |
| | if (p0.cost < p1.cost) { |
| | p1 = p0; |
| | } |
| |
|
| | |
| | if (mju_abs(p1.deriv[0]) < gtol) { |
| | if (p1.alpha == 0) { |
| | ctx->LSresult = 2; |
| | } else { |
| | ctx->LSresult = 0; |
| | } |
| | ctx->LSslope = mju_abs(p1.deriv[0])*slopescl; |
| | return p1.alpha; |
| | } |
| |
|
| | |
| | int dir = (p1.deriv[0] < 0 ? +1 : -1); |
| |
|
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| |
|
| | |
| | int p2update = 0; |
| | while (p1.deriv[0]*dir <= -gtol && ctx->LSiter < ls_iterations) { |
| | |
| | p2 = p1; |
| | p2update = 1; |
| |
|
| | |
| | p1.alpha -= p1.deriv[0]/p1.deriv[1]; |
| | CGeval(ctx, &p1); |
| |
|
| | |
| | if (mju_abs(p1.deriv[0]) < gtol) { |
| | ctx->LSslope = mju_abs(p1.deriv[0])*slopescl; |
| | return p1.alpha; |
| | } |
| | } |
| |
|
| | |
| | if (ctx->LSiter >= ls_iterations) { |
| | ctx->LSresult = 3; |
| | ctx->LSslope = mju_abs(p1.deriv[0])*slopescl; |
| | return p1.alpha; |
| | } |
| |
|
| | |
| | if (!p2update) { |
| | ctx->LSresult = 6; |
| | ctx->LSslope = mju_abs(p1.deriv[0])*slopescl; |
| | return p1.alpha; |
| | } |
| |
|
| | |
| | p2next = p1; |
| | p1next.alpha = p1.alpha - p1.deriv[0]/p1.deriv[1]; |
| | CGeval(ctx, &p1next); |
| |
|
| | |
| | while (ctx->LSiter < ls_iterations) { |
| | |
| | pmid.alpha = 0.5*(p1.alpha + p2.alpha); |
| | CGeval(ctx, &pmid); |
| |
|
| | |
| | mjCGPnt candidates[3] = {p1next, p2next, pmid}; |
| |
|
| | |
| | mjtNum bestcost = 0; |
| | int bestind = -1; |
| | for (int i=0; i < 3; i++) { |
| | if (mju_abs(candidates[i].deriv[0]) < gtol && |
| | (bestind == -1 || candidates[i].cost < bestcost)) { |
| | bestcost = candidates[i].cost; |
| | bestind = i; |
| | } |
| | } |
| | if (bestind >= 0) { |
| | ctx->LSslope = mju_abs(candidates[bestind].deriv[0])*slopescl; |
| | return candidates[bestind].alpha; |
| | } |
| |
|
| | |
| | int b1 = updateBracket(ctx, &p1, candidates, &p1next); |
| | int b2 = updateBracket(ctx, &p2, candidates, &p2next); |
| |
|
| | |
| | if (!b1 && !b2) { |
| | if (pmid.cost < p0.cost) { |
| | ctx->LSresult = 0; |
| | } else { |
| | ctx->LSresult = 7; |
| | } |
| |
|
| | ctx->LSslope = mju_abs(pmid.deriv[0])*slopescl; |
| | return pmid.alpha; |
| | } |
| | } |
| |
|
| | |
| | if (p1.cost <= p2.cost && p1.cost < p0.cost) { |
| | ctx->LSresult = 4; |
| | ctx->LSslope = mju_abs(p1.deriv[0])*slopescl; |
| | return p1.alpha; |
| | } else if (p2.cost <= p1.cost && p2.cost < p0.cost) { |
| | ctx->LSresult = 4; |
| | ctx->LSslope = mju_abs(p2.deriv[0])*slopescl; |
| | return p2.alpha; |
| | } else { |
| | ctx->LSresult = 5; |
| | return 0; |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | |
| | static void MakeHessian(mjData* d, mjCGContext* ctx) { |
| | int nv = ctx->nv, nefc = ctx->nefc; |
| |
|
| | |
| | for (int i=0; i < nefc; i++) { |
| | ctx->D[i] = ctx->efc_state[i] == mjCNSTRSTATE_QUADRATIC ? ctx->efc_D[i] : 0; |
| | } |
| |
|
| | |
| | if (ctx->is_sparse) { |
| | |
| | ctx->nH = mju_sqrMatTDSparseCount(ctx->H_rownnz, ctx->H_rowadr, nv, |
| | ctx->J_rownnz, ctx->J_rowadr, ctx->J_colind, |
| | ctx->JT_rownnz, ctx->JT_rowadr, ctx->JT_colind, |
| | ctx->JT_rowsuper, d, 0); |
| |
|
| | |
| | ctx->nH += ctx->M_rowadr[nv - 1] + ctx->M_rownnz[nv - 1]; |
| |
|
| | |
| | int shift = 0; |
| | for (int r = 0; r < nv - 1; r++) { |
| | shift += ctx->M_rownnz[r]; |
| | ctx->H_rowadr[r + 1] += shift; |
| | } |
| |
|
| | |
| | ctx->H_colind = mjSTACKALLOC(d, ctx->nH, int); |
| | ctx->H = mjSTACKALLOC(d, ctx->nH, mjtNum); |
| |
|
| | |
| | mju_sqrMatTDSparse(ctx->H, ctx->J, ctx->JT, ctx->D, nefc, nv, |
| | ctx->H_rownnz, ctx->H_rowadr, ctx->H_colind, |
| | ctx->J_rownnz, ctx->J_rowadr, ctx->J_colind, NULL, |
| | ctx->JT_rownnz, ctx->JT_rowadr, ctx->JT_colind, ctx->JT_rowsuper, |
| | d, NULL); |
| |
|
| | |
| | mju_addToMatSparse(ctx->H, ctx->H_rownnz, ctx->H_rowadr, ctx->H_colind, nv, |
| | ctx->M, ctx->M_rownnz, ctx->M_rowadr, ctx->M_colind, |
| | ctx->buf_val, ctx->buf_ind); |
| |
|
| | |
| | mj_markStack(d); |
| | int* HT_rownnz = mjSTACKALLOC(d, nv, int); |
| | int* HT_rowadr = mjSTACKALLOC(d, nv, int); |
| | int* HT_colind = mjSTACKALLOC(d, ctx->nH, int); |
| | mju_transposeSparse(NULL, NULL, nv, nv, |
| | HT_rownnz, HT_rowadr, HT_colind, NULL, |
| | ctx->H_rownnz, ctx->H_rowadr, ctx->H_colind); |
| |
|
| | |
| | ctx->nL = mju_cholFactorCount(ctx->L_rownnz, HT_rownnz, HT_rowadr, HT_colind, nv, d); |
| | mj_freeStack(d); |
| |
|
| | |
| | ctx->L_rowadr[0] = 0; |
| | for (int r=1; r < nv; r++) { |
| | ctx->L_rowadr[r] = ctx->L_rowadr[r-1] + ctx->L_rownnz[r-1]; |
| | } |
| |
|
| | |
| | ctx->L_colind = mjSTACKALLOC(d, ctx->nL, int); |
| | ctx->L = mjSTACKALLOC(d, ctx->nL, mjtNum); |
| | if (ctx->is_elliptic) { |
| | ctx->Lcone = mjSTACKALLOC(d, ctx->nL, mjtNum); |
| | } |
| |
|
| | |
| | for (int r = 0; r < nv; r++) { |
| | const int* colind = ctx->H_colind + ctx->H_rowadr[r]; |
| | int rownnz = ctx->H_rownnz[r]; |
| |
|
| | |
| | int nnz = 1; |
| | while (nnz < rownnz && colind[nnz - 1] < r) { |
| | nnz++; |
| | } |
| |
|
| | |
| | if (colind[nnz - 1] != r) { |
| | mjERROR("Newton solver Hessian has zero diagonal on row %d", r); |
| | } |
| |
|
| | |
| | ctx->H_lowernnz[r] = nnz; |
| | } |
| | } |
| |
|
| | |
| | else { |
| | |
| | ctx->nL = nv*nv; |
| | ctx->L = mjSTACKALLOC(d, ctx->nL, mjtNum); |
| | if (ctx->is_elliptic) { |
| | ctx->Lcone = mjSTACKALLOC(d, ctx->nL, mjtNum); |
| | } |
| |
|
| | |
| | mju_sqrMatTD_impl(ctx->L, ctx->J, ctx->D, nefc, nv, 0); |
| | mju_addToSymSparse(ctx->L, ctx->M, ctx->nv, |
| | ctx->M_rownnz, ctx->M_rowadr, ctx->M_colind, |
| | 0); |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | static void HessianCone(mjData* d, mjCGContext* ctx); |
| |
|
| | |
| | static void FactorizeHessian(mjData* d, mjCGContext* ctx, int flg_recompute) { |
| | int nv = ctx->nv, nefc = ctx->nefc; |
| |
|
| | |
| | if (flg_recompute) { |
| | for (int i=0; i < nefc; i++) { |
| | ctx->D[i] = ctx->efc_state[i] == mjCNSTRSTATE_QUADRATIC ? ctx->efc_D[i] : 0; |
| | } |
| | } |
| |
|
| | |
| | if (ctx->is_sparse) { |
| | |
| | if (flg_recompute) { |
| | |
| | mju_sqrMatTDSparse(ctx->H, ctx->J, ctx->JT, ctx->D, nefc, nv, |
| | ctx->H_rownnz, ctx->H_rowadr, ctx->H_colind, |
| | ctx->J_rownnz, ctx->J_rowadr, ctx->J_colind, NULL, |
| | ctx->JT_rownnz, ctx->JT_rowadr, ctx->JT_colind, ctx->JT_rowsuper, |
| | d, NULL); |
| |
|
| | |
| | mju_addToMatSparse(ctx->H, ctx->H_rownnz, ctx->H_rowadr, ctx->H_colind, nv, |
| | ctx->M, ctx->M_rownnz, ctx->M_rowadr, ctx->M_colind, |
| | ctx->buf_val, ctx->buf_ind); |
| | } |
| |
|
| | |
| | for (int r = 0; r < nv; r++) { |
| | int nnz = ctx->H_lowernnz[r]; |
| | mju_copy(ctx->L + ctx->L_rowadr[r], ctx->H + ctx->H_rowadr[r], nnz); |
| | mju_copyInt(ctx->L_colind + ctx->L_rowadr[r], ctx->H_colind + ctx->H_rowadr[r], nnz); |
| | ctx->L_rownnz[r] = nnz; |
| | } |
| |
|
| | |
| | int rank = mju_cholFactorSparse(ctx->L, nv, mjMINVAL, |
| | ctx->L_rownnz, ctx->L_rowadr, ctx->L_colind, d); |
| |
|
| | |
| | if (rank != nv) { |
| | mjERROR("rank-deficient sparse Hessian"); |
| | } |
| |
|
| | |
| | if (ctx->nL != ctx->L_rowadr[nv-1] + ctx->L_rownnz[nv-1]) { |
| | mjERROR("mismatch between pre-counted and post-factorization L nonzeros"); |
| | } |
| | } |
| |
|
| | |
| | else { |
| | |
| | if (flg_recompute) { |
| | mju_sqrMatTD_impl(ctx->L, ctx->J, ctx->D, nefc, nv, 0); |
| | mju_addToSymSparse(ctx->L, ctx->M, ctx->nv, |
| | ctx->M_rownnz, ctx->M_rowadr, ctx->M_colind, |
| | 0); |
| | } |
| |
|
| | |
| | mju_cholFactor(ctx->L, nv, mjMINVAL); |
| | } |
| |
|
| | |
| | if (ctx->ncone) { |
| | HessianCone(d, ctx); |
| | } |
| |
|
| | |
| | ctx->nupdate = nefc; |
| | } |
| |
|
| |
|
| |
|
| | |
| | static void HessianCone(mjData* d, mjCGContext* ctx) { |
| | int nv = ctx->nv, nefc = ctx->nefc; |
| | mjtNum local[36]; |
| |
|
| | |
| | mju_copy(ctx->Lcone, ctx->L, ctx->nL); |
| |
|
| | mj_markStack(d); |
| |
|
| | |
| | mjtNum* LTJ = mjSTACKALLOC(d, 6*nv, mjtNum); |
| | mjtNum* LTJ_row = mjSTACKALLOC(d, nv, mjtNum); |
| | int* LTJ_ind = mjSTACKALLOC(d, nv, int); |
| |
|
| | |
| | for (int i=0; i < nefc; i++) { |
| | if (ctx->efc_state[i] == mjCNSTRSTATE_CONE) { |
| | mjContact* con = ctx->contact + ctx->efc_id[i]; |
| | int dim = con->dim; |
| |
|
| | |
| | mju_copy(local, con->H, dim*dim); |
| | mju_cholFactor(local, dim, mjMINVAL); |
| |
|
| | |
| | if (ctx->is_sparse) { |
| | |
| | const int nnz = ctx->J_rownnz[i]; |
| |
|
| | |
| | mju_zero(LTJ, dim*nnz); |
| | for (int r=0; r < dim; r++) { |
| | for (int c=0; c <= r; c++) { |
| | mju_addToScl(LTJ+c*nnz, ctx->J+ctx->J_rowadr[i+r], local[r*dim+c], nnz); |
| | } |
| | } |
| |
|
| | |
| | for (int r=0; r < dim; r++) { |
| | |
| | mju_copy(LTJ_row, LTJ+r*nnz, nnz); |
| | mju_copyInt(LTJ_ind, ctx->J_colind+ctx->J_rowadr[i+r], nnz); |
| |
|
| | |
| | mju_cholUpdateSparse(ctx->Lcone, LTJ_row, nv, 1, |
| | ctx->L_rownnz, ctx->L_rowadr, ctx->L_colind, nnz, LTJ_ind, d); |
| | } |
| | } |
| |
|
| | |
| | else { |
| | |
| | mju_zero(LTJ, dim*nv); |
| | for (int r=0; r < dim; r++) { |
| | for (int c=0; c <= r; c++) { |
| | mju_addToScl(LTJ+c*nv, ctx->J+(i+r)*nv, local[r*dim+c], nv); |
| | } |
| | } |
| |
|
| | |
| | for (int r=0; r < dim; r++) { |
| | mju_cholUpdate(ctx->Lcone, LTJ+r*nv, nv, 1); |
| | } |
| | } |
| |
|
| | |
| | ctx->nupdate += dim; |
| |
|
| | |
| | i += (dim-1); |
| | } |
| | } |
| |
|
| | mj_freeStack(d); |
| | } |
| |
|
| |
|
| |
|
| | |
| | static void HessianIncremental(mjData* d, mjCGContext* ctx, const int* oldstate) { |
| | int rank, nv = ctx->nv, nefc = ctx->nefc; |
| | mj_markStack(d); |
| |
|
| | |
| | mjtNum* vec = mjSTACKALLOC(d, nv, mjtNum); |
| | int* vec_ind = mjSTACKALLOC(d, nv, int); |
| |
|
| | |
| | ctx->nupdate = 0; |
| |
|
| | |
| | for (int i=0; i < nefc; i++) { |
| | int flag_update = -1; |
| |
|
| | |
| | if (oldstate[i] != mjCNSTRSTATE_QUADRATIC && ctx->efc_state[i] == mjCNSTRSTATE_QUADRATIC) { |
| | flag_update = 1; |
| | } |
| |
|
| | |
| | else if (oldstate[i] == mjCNSTRSTATE_QUADRATIC && ctx->efc_state[i] != mjCNSTRSTATE_QUADRATIC) { |
| | flag_update = 0; |
| | } |
| |
|
| | |
| | if (flag_update != -1) { |
| | |
| | if (ctx->is_sparse) { |
| | |
| | const int nnz = ctx->J_rownnz[i], adr = ctx->J_rowadr[i]; |
| |
|
| | |
| | mju_scl(vec, ctx->J+adr, mju_sqrt(ctx->efc_D[i]), nnz); |
| | mju_copyInt(vec_ind, ctx->J_colind+adr, nnz); |
| |
|
| | |
| | rank = mju_cholUpdateSparse(ctx->L, vec, nv, flag_update, |
| | ctx->L_rownnz, ctx->L_rowadr, ctx->L_colind, nnz, vec_ind, |
| | d); |
| | } else { |
| | mju_scl(vec, ctx->J+i*nv, mju_sqrt(ctx->efc_D[i]), nv); |
| | rank = mju_cholUpdate(ctx->L, vec, nv, flag_update); |
| | } |
| | ctx->nupdate++; |
| |
|
| | |
| | if (rank < nv) { |
| | mj_freeStack(d); |
| | FactorizeHessian(d, ctx, 1); |
| |
|
| | |
| | return; |
| | } |
| | } |
| | } |
| |
|
| | |
| | if (ctx->ncone) { |
| | HessianCone(d, ctx); |
| | } |
| |
|
| | mj_freeStack(d); |
| | } |
| |
|
| |
|
| |
|
| | |
| | static void mj_solCGNewton(const mjModel* m, mjData* d, int island, int maxiter, int flg_Newton) { |
| | int iter = 0; |
| | mjtNum alpha, beta; |
| | mjtNum *gradold = NULL, *Mgradold = NULL, *Mgraddif = NULL; |
| | mjCGContext ctx; |
| | mj_markStack(d); |
| |
|
| | |
| | CGpointers(m, d, &ctx, island); |
| | CGallocate(d, &ctx, flg_Newton); |
| |
|
| | |
| | int nv = ctx.nv; |
| | int nefc = ctx.nefc; |
| |
|
| | |
| | if (!flg_Newton) { |
| | gradold = mjSTACKALLOC(d, nv, mjtNum); |
| | Mgradold = mjSTACKALLOC(d, nv, mjtNum); |
| | Mgraddif = mjSTACKALLOC(d, nv, mjtNum); |
| | } |
| | int* oldstate = mjSTACKALLOC(d, nefc, int); |
| |
|
| | |
| | mju_mulSymVecSparse(ctx.Ma, ctx.M, ctx.qacc, nv, |
| | ctx.M_rownnz, ctx.M_rowadr, ctx.M_colind); |
| |
|
| |
|
| | |
| | if (!ctx.is_sparse) { |
| | mju_mulMatVec(ctx.Jaref, ctx.J, ctx.qacc, nefc, nv); |
| | } else { |
| | mju_mulMatVecSparse(ctx.Jaref, ctx.J, ctx.qacc, nefc, |
| | ctx.J_rownnz, ctx.J_rowadr, ctx.J_colind, ctx.J_rowsuper); |
| | } |
| | mju_subFrom(ctx.Jaref, ctx.efc_aref, nefc); |
| |
|
| | |
| | CGupdateConstraint(&ctx, flg_Newton & (m->opt.cone == mjCONE_ELLIPTIC)); |
| | if (flg_Newton) { |
| | |
| | MakeHessian(d, &ctx); |
| | FactorizeHessian(d, &ctx, 0); |
| | } |
| | CGupdateGradient(&ctx, flg_Newton); |
| |
|
| | |
| | mju_scl(ctx.search, ctx.Mgrad, -1, nv); |
| |
|
| | |
| | mjtNum scale; |
| | if (island < 0) { |
| | scale = 1 / (m->stat.meaninertia * mjMAX(1, m->nv)); |
| | } else { |
| | mjtNum island_inertia = 0; |
| | for (int i=0; i < nv; i++) { |
| | int diag_i = ctx.M_rowadr[i] + ctx.M_rownnz[i] - 1; |
| | island_inertia += ctx.M[diag_i]; |
| | } |
| | scale = 1 / island_inertia; |
| | } |
| | ctx.scale = scale; |
| |
|
| | |
| | while (iter < maxiter) { |
| | |
| | alpha = CGsearch(&ctx, m->opt.tolerance * m->opt.ls_tolerance, m->opt.ls_iterations); |
| |
|
| | |
| | if (alpha == 0) { |
| | break; |
| | } |
| |
|
| | |
| | mju_addToScl(ctx.qacc, ctx.search, alpha, nv); |
| | mju_addToScl(ctx.Ma, ctx.Mv, alpha, nv); |
| | mju_addToScl(ctx.Jaref, ctx.Jv, alpha, nefc); |
| |
|
| | |
| | if (!flg_Newton) { |
| | mju_copy(gradold, ctx.grad, nv); |
| | mju_copy(Mgradold, ctx.Mgrad, nv); |
| | } |
| | mju_copyInt(oldstate, ctx.efc_state, nefc); |
| | mjtNum oldcost = ctx.cost; |
| |
|
| | |
| | CGupdateConstraint(&ctx, flg_Newton & (m->opt.cone == mjCONE_ELLIPTIC)); |
| | if (flg_Newton) { |
| | HessianIncremental(d, &ctx, oldstate); |
| | } |
| | CGupdateGradient(&ctx, flg_Newton); |
| |
|
| | |
| | int nchange = 0; |
| | for (int i=0; i < nefc; i++) { |
| | nchange += (ctx.efc_state[i] != oldstate[i]); |
| | } |
| |
|
| | |
| | mjtNum improvement = scale * (oldcost - ctx.cost); |
| | mjtNum gradient = scale * mju_norm(ctx.grad, nv); |
| | saveStats(m, d, island, iter, improvement, gradient, ctx.LSslope, |
| | ctx.nactive, nchange, ctx.LSiter, ctx.nupdate); |
| |
|
| | |
| | iter++; |
| |
|
| | |
| | if (improvement < m->opt.tolerance || gradient < m->opt.tolerance) { |
| | break; |
| | } |
| |
|
| | |
| | if (flg_Newton) { |
| | mju_scl(ctx.search, ctx.Mgrad, -1, nv); |
| | } else { |
| | |
| | mju_sub(Mgraddif, ctx.Mgrad, Mgradold, nv); |
| | beta = mju_dot(ctx.grad, Mgraddif, nv) / |
| | mju_max(mjMINVAL, mju_dot(gradold, Mgradold, nv)); |
| |
|
| | |
| | if (beta < 0) { |
| | beta = 0; |
| | } |
| |
|
| | |
| | for (int i=0; i < nv; i++) { |
| | ctx.search[i] = -ctx.Mgrad[i] + beta*ctx.search[i]; |
| | } |
| | } |
| | } |
| |
|
| | |
| | if (island < mjNISLAND) { |
| | |
| | int island_stat = island < 0 ? 0 : island; |
| |
|
| | |
| | d->solver_niter[island_stat] += iter; |
| |
|
| | |
| | if (flg_Newton) { |
| | if (mj_isSparse(m)) { |
| | |
| | int num_factors = 1 + (ctx.Lcone != NULL); |
| | d->solver_nnz[island_stat] = num_factors * ctx.nL + ctx.nH; |
| | } else { |
| | d->solver_nnz[island_stat] = nv*nv; |
| | } |
| | } else { |
| | d->solver_nnz[island_stat] = 0; |
| | } |
| | } |
| |
|
| | mj_freeStack(d); |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mj_solCG(const mjModel* m, mjData* d, int maxiter) { |
| | mj_solCGNewton(m, d, -1, maxiter, 0); |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mj_solCG_island(const mjModel* m, mjData* d, int island, int maxiter) { |
| | mj_solCGNewton(m, d, island, maxiter, 0); |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mj_solNewton(const mjModel* m, mjData* d, int maxiter) { |
| | mj_solCGNewton(m, d, -1, maxiter, 1); |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mj_solNewton_island(const mjModel* m, mjData* d, int island, int maxiter) { |
| | mj_solCGNewton(m, d, island, maxiter, 1); |
| | } |
| |
|