| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| |
|
| | #include "engine/engine_derivative_fd.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_forward.h" |
| | #include "engine/engine_io.h" |
| | #include "engine/engine_inverse.h" |
| | #include "engine/engine_macro.h" |
| | #include "engine/engine_support.h" |
| | #include "engine/engine_util_blas.h" |
| | #include "engine/engine_util_errmem.h" |
| | #include "engine/engine_util_misc.h" |
| |
|
| |
|
| |
|
| | |
| |
|
| | |
| | static void getState(const mjModel* m, const mjData* d, mjtNum* state, mjtNum* sensordata) { |
| | mj_getState(m, d, state, mjSTATE_PHYSICS); |
| | if (sensordata) { |
| | mju_copy(sensordata, d->sensordata, m->nsensordata); |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | static void diff(mjtNum* restrict dx, const mjtNum* x1, const mjtNum* x2, mjtNum h, int n) { |
| | mjtNum inv_h = 1/h; |
| | for (int i=0; i < n; i++) { |
| | dx[i] = inv_h * (x2[i] - x1[i]); |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | static void stateDiff(const mjModel* m, mjtNum* ds, const mjtNum* s1, const mjtNum* s2, mjtNum h) { |
| | int nq = m->nq, nv = m->nv, na = m->na; |
| |
|
| | if (nq == nv) { |
| | diff(ds, s1, s2, h, nq+nv+na); |
| | } else { |
| | mj_differentiatePos(m, ds, h, s1, s2); |
| | diff(ds+nv, s1+nq, s2+nq, h, nv+na); |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | static void clampedDiff(mjtNum* dx, const mjtNum* x, const mjtNum* x_plus, const mjtNum* x_minus, |
| | mjtNum h, int nx) { |
| | if (x_plus && !x_minus) { |
| | |
| | diff(dx, x, x_plus, h, nx); |
| | } else if (!x_plus && x_minus) { |
| | |
| | diff(dx, x_minus, x, h, nx); |
| | } else if (x_plus && x_minus) { |
| | |
| | diff(dx, x_plus, x_minus, 2*h, nx); |
| | } else { |
| | |
| | mju_zero(dx, nx); |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | static void clampedStateDiff(const mjModel* m, mjtNum* ds, const mjtNum* s, const mjtNum* s_plus, |
| | const mjtNum* s_minus, mjtNum h) { |
| | if (s_plus && !s_minus) { |
| | |
| | stateDiff(m, ds, s, s_plus, h); |
| | } else if (!s_plus && s_minus) { |
| | |
| | stateDiff(m, ds, s_minus, s, h); |
| | } else if (s_plus && s_minus) { |
| | |
| | stateDiff(m, ds, s_minus, s_plus, 2*h); |
| | } else { |
| | |
| | mju_zero(ds, 2*m->nv + m->na); |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | static int inRange(const mjtNum x1, const mjtNum x2, const mjtNum* range) { |
| | return x1 >= range[0] && x1 <= range[1] && |
| | x2 >= range[0] && x2 <= range[1]; |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mj_stepSkip(const mjModel* m, mjData* d, int skipstage, int skipsensor) { |
| | TM_START; |
| |
|
| | |
| | mj_checkPos(m, d); |
| | mj_checkVel(m, d); |
| | mj_forwardSkip(m, d, skipstage, skipsensor); |
| | mj_checkAcc(m, d); |
| |
|
| | |
| | if (mjENABLED(mjENBL_FWDINV)) { |
| | mj_compareFwdInv(m, d); |
| | } |
| |
|
| | |
| | switch ((mjtIntegrator) m->opt.integrator) { |
| | case mjINT_EULER: |
| | mj_EulerSkip(m, d, skipstage >= mjSTAGE_POS); |
| | break; |
| |
|
| | case mjINT_RK4: |
| | |
| | mj_RungeKutta(m, d, 4); |
| | break; |
| |
|
| | case mjINT_IMPLICIT: |
| | case mjINT_IMPLICITFAST: |
| | mj_implicitSkip(m, d, skipstage >= mjSTAGE_VEL); |
| | break; |
| |
|
| | default: |
| | mjERROR("invalid integrator"); |
| | } |
| |
|
| | TM_END(mjTIMER_STEP); |
| | } |
| |
|
| |
|
| |
|
| | |
| | static void inverseSkip(const mjModel* m, mjData* d, mjtStage stage, int skipsensor, |
| | int flg_actuation, mjtNum* force) { |
| | mj_inverseSkip(m, d, stage, skipsensor); |
| | mju_copy(force, d->qfrc_inverse, m->nv); |
| | if (flg_actuation) { |
| | mj_fwdActuation(m, d); |
| | mju_subFrom(force, d->qfrc_actuator, m->nv); |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| |
|
| | |
| | void mjd_passive_velFD(const mjModel* m, mjData* d, mjtNum eps) { |
| | int nv = m->nv; |
| |
|
| | mj_markStack(d); |
| | mjtNum* qfrc_passive = mjSTACKALLOC(d, nv, mjtNum); |
| | mjtNum* fd = mjSTACKALLOC(d, nv, mjtNum); |
| | int* cnt = mjSTACKALLOC(d, nv, int); |
| |
|
| | |
| | mju_zeroInt(cnt, nv); |
| |
|
| | |
| | mju_copy(qfrc_passive, d->qfrc_passive, nv); |
| |
|
| | |
| | for (int i=0; i < nv; i++) { |
| | |
| | mjtNum saveqvel = d->qvel[i]; |
| |
|
| | |
| | d->qvel[i] = saveqvel + eps; |
| | mj_fwdVelocity(m, d); |
| |
|
| | |
| | d->qvel[i] = saveqvel; |
| |
|
| | |
| | mju_sub(fd, d->qfrc_passive, qfrc_passive, nv); |
| | mju_scl(fd, fd, 1/eps, nv); |
| |
|
| | |
| | for (int j=0; j < nv; j++) { |
| | int adr = d->D_rowadr[j] + cnt[j]; |
| | if (cnt[j] < d->D_rownnz[j] && d->D_colind[adr] == i) { |
| | d->qDeriv[adr] = fd[j]; |
| | cnt[j]++; |
| | } |
| | } |
| | } |
| |
|
| | |
| | mj_fwdVelocity(m, d); |
| |
|
| | mj_freeStack(d); |
| | } |
| |
|
| |
|
| |
|
| | |
| |
|
| | |
| | void mjd_smooth_velFD(const mjModel* m, mjData* d, mjtNum eps) { |
| | int nv = m->nv; |
| |
|
| | mj_markStack(d); |
| | mjtNum* plus = mjSTACKALLOC(d, nv, mjtNum); |
| | mjtNum* minus = mjSTACKALLOC(d, nv, mjtNum); |
| | mjtNum* fd = mjSTACKALLOC(d, nv, mjtNum); |
| | int* cnt = mjSTACKALLOC(d, nv, int); |
| |
|
| | |
| | mju_zeroInt(cnt, nv); |
| |
|
| | |
| | for (int i=0; i < nv; i++) { |
| | |
| | mjtNum saveqvel = d->qvel[i]; |
| |
|
| | |
| | d->qvel[i] = saveqvel + eps; |
| | mj_fwdVelocity(m, d); |
| | mj_fwdActuation(m, d); |
| | mju_add(plus, d->qfrc_actuator, d->qfrc_passive, nv); |
| | mju_subFrom(plus, d->qfrc_bias, nv); |
| |
|
| | |
| | d->qvel[i] = saveqvel - eps; |
| | mj_fwdVelocity(m, d); |
| | mj_fwdActuation(m, d); |
| | mju_add(minus, d->qfrc_actuator, d->qfrc_passive, nv); |
| | mju_subFrom(minus, d->qfrc_bias, nv); |
| |
|
| | |
| | d->qvel[i] = saveqvel; |
| |
|
| | |
| | mju_sub(fd, plus, minus, nv); |
| | mju_scl(fd, fd, 0.5/eps, nv); |
| |
|
| | |
| | for (int j=0; j < nv; j++) { |
| | if (cnt[j] < d->D_rownnz[j] && d->D_colind[d->D_rowadr[j]+cnt[j]] == i) { |
| | d->qDeriv[d->D_rowadr[j]+cnt[j]] = fd[j]; |
| | cnt[j]++; |
| | } |
| | } |
| | } |
| |
|
| | |
| | for (int i=0; i < nv; i++) { |
| | if (cnt[i] != d->D_rownnz[i]) { |
| | mjERROR("error in constructing FD sparse derivative"); |
| | } |
| | } |
| |
|
| | |
| | mj_fwdVelocity(m, d); |
| | mj_fwdActuation(m, d); |
| |
|
| | mj_freeStack(d); |
| | } |
| |
|
| |
|
| |
|
| | |
| |
|
| |
|
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | void mjd_stepFD(const mjModel* m, mjData* d, mjtNum eps, mjtByte flg_centered, |
| | mjtNum* DyDq, mjtNum* DyDv, mjtNum* DyDa, mjtNum* DyDu, |
| | mjtNum* DsDq, mjtNum* DsDv, mjtNum* DsDa, mjtNum* DsDu) { |
| | int nq = m->nq, nv = m->nv, na = m->na, nu = m->nu, ns = m->nsensordata; |
| | int ndx = 2*nv+na; |
| | mj_markStack(d); |
| |
|
| | |
| | unsigned int restore_spec = mjSTATE_FULLPHYSICS | mjSTATE_CTRL; |
| | restore_spec |= mjDISABLED(mjDSBL_WARMSTART) ? 0 : mjSTATE_WARMSTART; |
| |
|
| | mjtNum *fullstate = mjSTACKALLOC(d, mj_stateSize(m, restore_spec), mjtNum); |
| | mjtNum *state = mjSTACKALLOC(d, nq+nv+na, mjtNum); |
| | mjtNum *next = mjSTACKALLOC(d, nq+nv+na, mjtNum); |
| | mjtNum *next_plus = mjSTACKALLOC(d, nq+nv+na, mjtNum); |
| | mjtNum *next_minus = mjSTACKALLOC(d, nq+nv+na, mjtNum); |
| |
|
| | |
| | int skipsensor = !DsDq && !DsDv && !DsDa && !DsDu; |
| | mjtNum *sensor = skipsensor ? NULL : mjSTACKALLOC(d, ns, mjtNum); |
| | mjtNum *sensor_plus = skipsensor ? NULL : mjSTACKALLOC(d, ns, mjtNum); |
| | mjtNum *sensor_minus = skipsensor ? NULL : mjSTACKALLOC(d, ns, mjtNum); |
| |
|
| | |
| | mjtNum *ctrl = mjSTACKALLOC(d, nu, mjtNum); |
| |
|
| | |
| | mj_getState(m, d, fullstate, restore_spec); |
| | mju_copy(ctrl, d->ctrl, nu); |
| | getState(m, d, state, NULL); |
| |
|
| | |
| | mj_stepSkip(m, d, mjSTAGE_NONE, skipsensor); |
| |
|
| | |
| | getState(m, d, next, sensor); |
| |
|
| | |
| | mj_setState(m, d, fullstate, restore_spec); |
| |
|
| | |
| | if (DyDu || DsDu) { |
| | for (int i=0; i < nu; i++) { |
| | int limited = m->actuator_ctrllimited[i]; |
| | |
| | int nudge_fwd = !limited || inRange(ctrl[i], ctrl[i]+eps, m->actuator_ctrlrange+2*i); |
| | if (nudge_fwd) { |
| | |
| | d->ctrl[i] += eps; |
| |
|
| | |
| | mj_stepSkip(m, d, mjSTAGE_VEL, skipsensor); |
| | getState(m, d, next_plus, sensor_plus); |
| |
|
| | |
| | mj_setState(m, d, fullstate, restore_spec); |
| | } |
| |
|
| | |
| | int nudge_back = (flg_centered || !nudge_fwd) && |
| | (!limited || inRange(ctrl[i]-eps, ctrl[i], m->actuator_ctrlrange+2*i)); |
| | if (nudge_back) { |
| | |
| | d->ctrl[i] -= eps; |
| |
|
| | |
| | mj_stepSkip(m, d, mjSTAGE_VEL, skipsensor); |
| | getState(m, d, next_minus, sensor_minus); |
| |
|
| | |
| | mj_setState(m, d, fullstate, restore_spec); |
| | } |
| |
|
| | |
| | if (DyDu) { |
| | clampedStateDiff(m, DyDu+i*ndx, next, nudge_fwd ? next_plus : NULL, |
| | nudge_back ? next_minus : NULL, eps); |
| | } |
| |
|
| | |
| | if (DsDu) { |
| | clampedDiff(DsDu+i*ns, sensor, nudge_fwd ? sensor_plus : NULL, |
| | nudge_back ? sensor_minus : NULL, eps, ns); |
| | } |
| | } |
| | } |
| |
|
| | |
| | if (DyDa || DsDa) { |
| | for (int i=0; i < na; i++) { |
| | |
| | d->act[i] += eps; |
| |
|
| | |
| | mj_stepSkip(m, d, mjSTAGE_VEL, skipsensor); |
| | getState(m, d, next_plus, sensor_plus); |
| |
|
| | |
| | mj_setState(m, d, fullstate, restore_spec); |
| |
|
| | |
| | if (flg_centered) { |
| | |
| | d->act[i] -= eps; |
| |
|
| | |
| | mj_stepSkip(m, d, mjSTAGE_VEL, skipsensor); |
| | getState(m, d, next_minus, sensor_minus); |
| |
|
| | |
| | mj_setState(m, d, fullstate, restore_spec); |
| | } |
| |
|
| | |
| | if (DyDa) { |
| | if (!flg_centered) { |
| | stateDiff(m, DyDa+i*ndx, next, next_plus, eps); |
| | } else { |
| | stateDiff(m, DyDa+i*ndx, next_minus, next_plus, 2*eps); |
| | } |
| | } |
| |
|
| | |
| | if (DsDa) { |
| | if (!flg_centered) { |
| | diff(DsDa+i*ns, sensor, sensor_plus, eps, ns); |
| | } else { |
| | diff(DsDa+i*ns, sensor_minus, sensor_plus, 2*eps, ns); |
| | } |
| | } |
| | } |
| | } |
| |
|
| |
|
| | |
| | if (DyDv || DsDv) { |
| | for (int i=0; i < nv; i++) { |
| | |
| | d->qvel[i] += eps; |
| |
|
| | |
| | mj_stepSkip(m, d, mjSTAGE_POS, skipsensor); |
| | getState(m, d, next_plus, sensor_plus); |
| |
|
| | |
| | mj_setState(m, d, fullstate, restore_spec); |
| |
|
| | |
| | if (flg_centered) { |
| | |
| | d->qvel[i] -= eps; |
| |
|
| | |
| | mj_stepSkip(m, d, mjSTAGE_POS, skipsensor); |
| | getState(m, d, next_minus, sensor_minus); |
| |
|
| | |
| | mj_setState(m, d, fullstate, restore_spec); |
| | } |
| |
|
| | |
| | if (DyDv) { |
| | if (!flg_centered) { |
| | stateDiff(m, DyDv+i*ndx, next, next_plus, eps); |
| | } else { |
| | stateDiff(m, DyDv+i*ndx, next_minus, next_plus, 2*eps); |
| | } |
| | } |
| |
|
| | |
| | if (DsDv) { |
| | if (!flg_centered) { |
| | diff(DsDv+i*ns, sensor, sensor_plus, eps, ns); |
| | } else { |
| | diff(DsDv+i*ns, sensor_minus, sensor_plus, 2*eps, ns); |
| | } |
| | } |
| | } |
| | } |
| |
|
| | |
| | if (DyDq || DsDq) { |
| | mjtNum *dpos = mjSTACKALLOC(d, nv, mjtNum); |
| | for (int i=0; i < nv; i++) { |
| | |
| | mju_zero(dpos, nv); |
| | dpos[i] = 1; |
| | mj_integratePos(m, d->qpos, dpos, eps); |
| |
|
| | |
| | mj_stepSkip(m, d, mjSTAGE_NONE, skipsensor); |
| | getState(m, d, next_plus, sensor_plus); |
| |
|
| | |
| | mj_setState(m, d, fullstate, restore_spec); |
| |
|
| | |
| | if (flg_centered) { |
| | |
| | mju_zero(dpos, nv); |
| | dpos[i] = 1; |
| | mj_integratePos(m, d->qpos, dpos, -eps); |
| |
|
| | |
| | mj_stepSkip(m, d, mjSTAGE_NONE, skipsensor); |
| | getState(m, d, next_minus, sensor_minus); |
| |
|
| | |
| | mj_setState(m, d, fullstate, restore_spec); |
| | } |
| |
|
| | |
| | if (DyDq) { |
| | if (!flg_centered) { |
| | stateDiff(m, DyDq+i*ndx, next, next_plus, eps); |
| | } else { |
| | stateDiff(m, DyDq+i*ndx, next_minus, next_plus, 2*eps); |
| | } |
| | } |
| |
|
| | |
| | if (DsDq) { |
| | if (!flg_centered) { |
| | diff(DsDq+i*ns, sensor, sensor_plus, eps, ns); |
| | } else { |
| | diff(DsDq+i*ns, sensor_minus, sensor_plus, 2*eps, ns); |
| | } |
| | } |
| | } |
| | } |
| |
|
| | mj_freeStack(d); |
| | } |
| |
|
| |
|
| |
|
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | void mjd_transitionFD(const mjModel* m, mjData* d, mjtNum eps, mjtByte flg_centered, |
| | mjtNum* A, mjtNum* B, mjtNum* C, mjtNum* D) { |
| | if (m->opt.integrator == mjINT_RK4) { |
| | mjERROR("RK4 integrator is not supported"); |
| | } |
| |
|
| | int nv = m->nv, na = m->na, nu = m->nu, ns = m->nsensordata; |
| | int ndx = 2*nv+na; |
| |
|
| | |
| | mjtNum *DyDq, *DyDv, *DyDa, *DsDq, *DsDv, *DsDa; |
| | DyDq = DyDv = DyDa = DsDq = DsDv = DsDa = NULL; |
| |
|
| | mj_markStack(d); |
| |
|
| | |
| | mjtNum *AT = A ? mjSTACKALLOC(d, ndx*ndx, mjtNum) : NULL; |
| | mjtNum *BT = B ? mjSTACKALLOC(d, nu*ndx, mjtNum) : NULL; |
| | mjtNum *CT = C ? mjSTACKALLOC(d, ndx*ns, mjtNum) : NULL; |
| | mjtNum *DT = D ? mjSTACKALLOC(d, nu*ns, mjtNum) : NULL; |
| |
|
| | |
| | if (A) { |
| | DyDq = AT; |
| | DyDv = AT+ndx*nv; |
| | DyDa = AT+ndx*2*nv; |
| | } |
| |
|
| | if (C) { |
| | DsDq = CT; |
| | DsDv = CT + ns*nv; |
| | DsDa = CT + ns*2*nv; |
| | } |
| |
|
| | |
| | mjd_stepFD(m, d, eps, flg_centered, DyDq, DyDv, DyDa, BT, DsDq, DsDv, DsDa, DT); |
| |
|
| |
|
| | |
| | if (A) mju_transpose(A, AT, ndx, ndx); |
| | if (B) mju_transpose(B, BT, nu, ndx); |
| | if (C) mju_transpose(C, CT, ndx, ns); |
| | if (D) mju_transpose(D, DT, nu, ns); |
| |
|
| | mj_freeStack(d); |
| | } |
| |
|
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | void mjd_inverseFD(const mjModel* m, mjData* d, mjtNum eps, mjtByte flg_actuation, |
| | mjtNum *DfDq, mjtNum *DfDv, mjtNum *DfDa, |
| | mjtNum *DsDq, mjtNum *DsDv, mjtNum *DsDa, |
| | mjtNum *DmDq) { |
| | int nq = m->nq, nv = m->nv, nM = m->nM, ns = m->nsensordata; |
| |
|
| | if (m->opt.integrator == mjINT_RK4) { |
| | mjERROR("RK4 integrator is not supported"); |
| | } |
| |
|
| | if (m->opt.noslip_iterations) { |
| | mjERROR("noslip solver is not supported"); |
| | } |
| |
|
| | |
| | int skipsensor = !DsDq && !DsDv && !DsDa; |
| |
|
| | |
| | mj_markStack(d); |
| | mjtNum *pos = mjSTACKALLOC(d, nq, mjtNum); |
| | mjtNum *force = mjSTACKALLOC(d, nv, mjtNum); |
| | mjtNum *force_plus = mjSTACKALLOC(d, nv, mjtNum); |
| | mjtNum *sensor = skipsensor ? NULL : mjSTACKALLOC(d, ns, mjtNum); |
| | mjtNum *mass = DmDq ? mjSTACKALLOC(d, nM, mjtNum) : NULL; |
| |
|
| | |
| | mju_copy(pos, d->qpos, nq); |
| |
|
| | |
| | inverseSkip(m, d, mjSTAGE_NONE, skipsensor, flg_actuation, force); |
| | if (sensor) mju_copy(sensor, d->sensordata, ns); |
| | if (mass) mju_copy(mass, d->qM, nM); |
| |
|
| | |
| | if (DfDa || DsDa) { |
| | for (int i=0; i < nv; i++) { |
| | |
| | mjtNum tmp = d->qacc[i]; |
| | d->qacc[i] += eps; |
| |
|
| | |
| | inverseSkip(m, d, mjSTAGE_VEL, skipsensor, flg_actuation, force_plus); |
| |
|
| | |
| | d->qacc[i] = tmp; |
| |
|
| | |
| | if (DfDa) diff(DfDa + i*nv, force, force_plus, eps, nv); |
| |
|
| | |
| | if (DsDa) diff(DsDa + i*ns, sensor, d->sensordata, eps, ns); |
| | } |
| | } |
| |
|
| | |
| | if (DfDv || DsDv) { |
| | for (int i=0; i < nv; i++) { |
| | |
| | mjtNum tmp = d->qvel[i]; |
| | d->qvel[i] += eps; |
| |
|
| | |
| | inverseSkip(m, d, mjSTAGE_POS, skipsensor, flg_actuation, force_plus); |
| |
|
| | |
| | d->qvel[i] = tmp; |
| |
|
| | |
| | if (DfDv) diff(DfDv + i*nv, force, force_plus, eps, nv); |
| |
|
| | |
| | if (DsDv) diff(DsDv + i*ns, sensor, d->sensordata, eps, ns); |
| | } |
| | } |
| |
|
| | |
| | if (DfDq || DsDq || DmDq) { |
| | mjtNum *dpos = mjSTACKALLOC(d, nv, mjtNum); |
| | for (int i=0; i < nv; i++) { |
| | |
| | mju_zero(dpos, nv); |
| | dpos[i] = 1.0; |
| | mj_integratePos(m, d->qpos, dpos, eps); |
| |
|
| | |
| | inverseSkip(m, d, mjSTAGE_NONE, skipsensor, flg_actuation, force_plus); |
| |
|
| | |
| | mju_copy(d->qpos, pos, nq); |
| |
|
| | |
| | if (DfDq) diff(DfDq + i*nv, force, force_plus, eps, nv); |
| |
|
| | |
| | if (DsDq) diff(DsDq + i*ns, sensor, d->sensordata, eps, ns); |
| |
|
| | |
| | if (DmDq) diff(DmDq + i*nM, mass, d->qM, eps, nM); |
| | } |
| | } |
| |
|
| | mj_freeStack(d); |
| | } |
| |
|