| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| |
|
| | #include "engine/engine_sensor.h" |
| |
|
| | #include <stddef.h> |
| |
|
| | #include <mujoco/mjdata.h> |
| | #include <mujoco/mjmodel.h> |
| | #include <mujoco/mjplugin.h> |
| | #include <mujoco/mjsan.h> |
| | #include "engine/engine_callback.h" |
| | #include "engine/engine_core_smooth.h" |
| | #include "engine/engine_crossplatform.h" |
| | #include "engine/engine_io.h" |
| | #include "engine/engine_plugin.h" |
| | #include "engine/engine_ray.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_spatial.h" |
| |
|
| |
|
| |
|
| | |
| |
|
| | |
| | static void apply_cutoff(const mjModel* m, mjData* d, mjtStage stage) { |
| | |
| | for (int i=0; i < m->nsensor; i++) { |
| | if (m->sensor_needstage[i] == stage && m->sensor_cutoff[i] > 0) { |
| | |
| | if (m->sensor_type[i] == mjSENS_GEOMFROMTO) { |
| | continue; |
| | } |
| |
|
| | |
| | int adr = m->sensor_adr[i]; |
| | int dim = m->sensor_dim[i]; |
| | mjtNum cutoff = m->sensor_cutoff[i]; |
| |
|
| | |
| | for (int j=0; j < dim; j++) { |
| | |
| | if (m->sensor_datatype[i] == mjDATATYPE_REAL) { |
| | d->sensordata[adr+j] = mju_clip(d->sensordata[adr+j], -cutoff, cutoff); |
| | } |
| |
|
| | |
| | else if (m->sensor_datatype[i] == mjDATATYPE_POSITIVE) { |
| | d->sensordata[adr+j] = mju_min(cutoff, d->sensordata[adr+j]); |
| | } |
| | } |
| | } |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | static void get_xpos_xmat(const mjData* d, mjtObj type, int id, int sensor_id, |
| | mjtNum **xpos, mjtNum **xmat) { |
| | switch (type) { |
| | case mjOBJ_XBODY: |
| | *xpos = d->xpos + 3*id; |
| | *xmat = d->xmat + 9*id; |
| | break; |
| | case mjOBJ_BODY: |
| | *xpos = d->xipos + 3*id; |
| | *xmat = d->ximat + 9*id; |
| | break; |
| | case mjOBJ_GEOM: |
| | *xpos = d->geom_xpos + 3*id; |
| | *xmat = d->geom_xmat + 9*id; |
| | break; |
| | case mjOBJ_SITE: |
| | *xpos = d->site_xpos + 3*id; |
| | *xmat = d->site_xmat + 9*id; |
| | break; |
| | case mjOBJ_CAMERA: |
| | *xpos = d->cam_xpos + 3*id; |
| | *xmat = d->cam_xmat + 9*id; |
| | break; |
| | default: |
| | mjERROR("invalid object type in sensor %d", sensor_id); |
| | } |
| | } |
| |
|
| | |
| | static void get_xquat(const mjModel* m, const mjData* d, mjtObj type, int id, int sensor_id, |
| | mjtNum *quat) { |
| | switch (type) { |
| | case mjOBJ_XBODY: |
| | mju_copy4(quat, d->xquat+4*id); |
| | break; |
| | case mjOBJ_BODY: |
| | mju_mulQuat(quat, d->xquat+4*id, m->body_iquat+4*id); |
| | break; |
| | case mjOBJ_GEOM: |
| | mju_mulQuat(quat, d->xquat+4*m->geom_bodyid[id], m->geom_quat+4*id); |
| | break; |
| | case mjOBJ_SITE: |
| | mju_mulQuat(quat, d->xquat+4*m->site_bodyid[id], m->site_quat+4*id); |
| | break; |
| | case mjOBJ_CAMERA: |
| | mju_mulQuat(quat, d->xquat+4*m->cam_bodyid[id], m->cam_quat+4*id); |
| | break; |
| | default: |
| | mjERROR("invalid object type in sensor %d", sensor_id); |
| | } |
| | } |
| |
|
| |
|
| | static void cam_project(mjtNum sensordata[2], const mjtNum target_xpos[3], |
| | const mjtNum cam_xpos[3], const mjtNum cam_xmat[9], |
| | const int cam_res[2], mjtNum cam_fovy, |
| | const float cam_intrinsic[4], const float cam_sensorsize[2]) { |
| | mjtNum fx, fy; |
| |
|
| | |
| | mjtNum translation[4][4] = {0}; |
| | translation[0][0] = 1; |
| | translation[1][1] = 1; |
| | translation[2][2] = 1; |
| | translation[3][3] = 1; |
| | translation[0][3] = -cam_xpos[0]; |
| | translation[1][3] = -cam_xpos[1]; |
| | translation[2][3] = -cam_xpos[2]; |
| |
|
| | |
| | mjtNum rotation[4][4] = {0}; |
| | rotation[0][0] = 1; |
| | rotation[1][1] = 1; |
| | rotation[2][2] = 1; |
| | rotation[3][3] = 1; |
| | for (int i=0; i < 3; i++) { |
| | for (int j=0; j < 3; j++) { |
| | rotation[i][j] = cam_xmat[j*3+i]; |
| | } |
| | } |
| |
|
| | |
| | if (cam_sensorsize[0] && cam_sensorsize[1]) { |
| | fx = cam_intrinsic[0] / cam_sensorsize[0] * cam_res[0]; |
| | fy = cam_intrinsic[1] / cam_sensorsize[1] * cam_res[1]; |
| | } else { |
| | fx = fy = .5 / mju_tan(cam_fovy * mjPI / 360.) * cam_res[1]; |
| | } |
| |
|
| | mjtNum focal[3][4] = {0}; |
| | focal[0][0] = -fx; |
| | focal[1][1] = fy; |
| | focal[2][2] = 1.0; |
| |
|
| | |
| | mjtNum image[3][3] = {0}; |
| | image[0][0] = 1; |
| | image[1][1] = 1; |
| | image[2][2] = 1; |
| | image[0][2] = (mjtNum)cam_res[0] / 2.0; |
| | image[1][2] = (mjtNum)cam_res[1] / 2.0; |
| |
|
| | |
| | mjtNum proj[3][4] = {0}; |
| | for (int i=0; i < 3; i++) { |
| | for (int j=0; j < 3; j++) { |
| | for (int k=0; k < 4; k++) { |
| | for (int l=0; l < 4; l++) { |
| | for (int n=0; n < 4; n++) { |
| | proj[i][n] += image[i][j] * focal[j][k] * rotation[k][l] * translation[l][n]; |
| | } |
| | } |
| | } |
| | } |
| | } |
| |
|
| | |
| | mjtNum pos_hom[4] = {0, 0, 0, 1}; |
| | mju_copy3(pos_hom, target_xpos); |
| |
|
| | |
| | |
| | mjtNum pixel_coord_hom[3] = {0}; |
| | for (int i=0; i < 3; i++) { |
| | for (int j=0; j < 4; j++) { |
| | pixel_coord_hom[i] += proj[i][j] * pos_hom[j]; |
| | } |
| | } |
| |
|
| | |
| | mjtNum denom = pixel_coord_hom[2]; |
| | if (mju_abs(denom) < mjMINVAL) { |
| | if (denom < 0) { |
| | denom = mju_min(denom, -mjMINVAL); |
| | } else { |
| | denom = mju_max(denom, mjMINVAL); |
| | } |
| | } |
| |
|
| | |
| | sensordata[0] = pixel_coord_hom[0] / denom; |
| | sensordata[1] = pixel_coord_hom[1] / denom; |
| | } |
| |
|
| |
|
| |
|
| | |
| |
|
| | |
| | void mj_sensorPos(const mjModel* m, mjData* d) { |
| | int ne = d->ne, nf = d->nf, nefc = d->nefc, nsensor = m->nsensor; |
| | int nusersensor = 0; |
| |
|
| | |
| | if (mjDISABLED(mjDSBL_SENSOR)) { |
| | return; |
| | } |
| |
|
| | |
| | for (int i=0; i < nsensor; i++) { |
| | mjtSensor type = (mjtSensor) m->sensor_type[i]; |
| |
|
| | |
| | if (type == mjSENS_PLUGIN) { |
| | continue; |
| | } |
| |
|
| | if (m->sensor_needstage[i] == mjSTAGE_POS) { |
| | |
| | int objtype = m->sensor_objtype[i]; |
| | int objid = m->sensor_objid[i]; |
| | int refid = m->sensor_refid[i]; |
| | int reftype = m->sensor_reftype[i]; |
| | int adr = m->sensor_adr[i]; |
| |
|
| | mjtNum rvec[3], *xpos, *xmat, *xpos_ref, *xmat_ref; |
| |
|
| | |
| | switch (type) { |
| | case mjSENS_MAGNETOMETER: |
| | mju_mulMatTVec(d->sensordata+adr, d->site_xmat+9*objid, m->opt.magnetic, 3, 3); |
| | break; |
| |
|
| | case mjSENS_CAMPROJECTION: |
| | cam_project(d->sensordata+adr, d->site_xpos+3*objid, d->cam_xpos+3*refid, |
| | d->cam_xmat+9*refid, m->cam_resolution+2*refid, m->cam_fovy[refid], |
| | m->cam_intrinsic+4*refid, m->cam_sensorsize+2*refid); |
| | break; |
| |
|
| | case mjSENS_RANGEFINDER: |
| | rvec[0] = d->site_xmat[9*objid+2]; |
| | rvec[1] = d->site_xmat[9*objid+5]; |
| | rvec[2] = d->site_xmat[9*objid+8]; |
| | d->sensordata[adr] = mj_ray(m, d, d->site_xpos+3*objid, rvec, NULL, 1, |
| | m->site_bodyid[objid], NULL); |
| |
|
| | break; |
| |
|
| | case mjSENS_JOINTPOS: |
| | d->sensordata[adr] = d->qpos[m->jnt_qposadr[objid]]; |
| | break; |
| |
|
| | case mjSENS_TENDONPOS: |
| | d->sensordata[adr] = d->ten_length[objid]; |
| | break; |
| |
|
| | case mjSENS_ACTUATORPOS: |
| | d->sensordata[adr] = d->actuator_length[objid]; |
| | break; |
| |
|
| | case mjSENS_BALLQUAT: |
| | mju_copy4(d->sensordata+adr, d->qpos+m->jnt_qposadr[objid]); |
| | mju_normalize4(d->sensordata+adr); |
| | break; |
| |
|
| | case mjSENS_JOINTLIMITPOS: |
| | d->sensordata[adr] = 0; |
| | for (int j=ne+nf; j < nefc; j++) { |
| | if (d->efc_type[j] == mjCNSTR_LIMIT_JOINT && d->efc_id[j] == objid) { |
| | d->sensordata[adr] = d->efc_pos[j] - d->efc_margin[j]; |
| | break; |
| | } |
| | } |
| | break; |
| |
|
| | case mjSENS_TENDONLIMITPOS: |
| | d->sensordata[adr] = 0; |
| | for (int j=ne+nf; j < nefc; j++) { |
| | if (d->efc_type[j] == mjCNSTR_LIMIT_TENDON && d->efc_id[j] == objid) { |
| | d->sensordata[adr] = d->efc_pos[j] - d->efc_margin[j]; |
| | break; |
| | } |
| | } |
| | break; |
| |
|
| | case mjSENS_FRAMEPOS: |
| | case mjSENS_FRAMEXAXIS: |
| | case mjSENS_FRAMEYAXIS: |
| | case mjSENS_FRAMEZAXIS: |
| | |
| | get_xpos_xmat(d, objtype, objid, i, &xpos, &xmat); |
| |
|
| | |
| | if (refid == -1) { |
| | if (type == mjSENS_FRAMEPOS) { |
| | mju_copy3(d->sensordata+adr, xpos); |
| | } else { |
| | |
| | int offset = type - mjSENS_FRAMEXAXIS; |
| | d->sensordata[adr] = xmat[offset]; |
| | d->sensordata[adr+1] = xmat[offset+3]; |
| | d->sensordata[adr+2] = xmat[offset+6]; |
| | } |
| | } |
| |
|
| | |
| | else { |
| | get_xpos_xmat(d, reftype, refid, i, &xpos_ref, &xmat_ref); |
| | if (type == mjSENS_FRAMEPOS) { |
| | mju_sub3(rvec, xpos, xpos_ref); |
| | mju_mulMatTVec3(d->sensordata+adr, xmat_ref, rvec); |
| | } else { |
| | |
| | int offset = type - mjSENS_FRAMEXAXIS; |
| | mjtNum axis[3] = {xmat[offset], xmat[offset+3], xmat[offset+6]}; |
| | mju_mulMatTVec3(d->sensordata+adr, xmat_ref, axis); |
| | } |
| | } |
| | break; |
| |
|
| | case mjSENS_FRAMEQUAT: |
| | { |
| | |
| | mjtNum objquat[4]; |
| | get_xquat(m, d, objtype, objid, i, objquat); |
| |
|
| | |
| | if (refid == -1) { |
| | mju_copy4(d->sensordata+adr, objquat); |
| | } else { |
| | |
| | mjtNum refquat[4]; |
| | get_xquat(m, d, reftype, refid, i, refquat); |
| |
|
| | |
| | mju_negQuat(refquat, refquat); |
| | mju_mulQuat(d->sensordata+adr, refquat, objquat); |
| | } |
| | } |
| | break; |
| |
|
| | case mjSENS_SUBTREECOM: |
| | mju_copy3(d->sensordata+adr, d->subtree_com+3*objid); |
| | break; |
| |
|
| | case mjSENS_INSIDESITE: |
| | get_xpos_xmat(d, objtype, objid, i, &xpos, &xmat); |
| | d->sensordata[adr] = mju_insideGeom(d->site_xpos + 3*refid, |
| | d->site_xmat + 9*refid, |
| | m->site_size + 3*refid, |
| | m->site_type[refid], |
| | xpos); |
| | break; |
| |
|
| | case mjSENS_GEOMDIST: |
| | case mjSENS_GEOMNORMAL: |
| | case mjSENS_GEOMFROMTO: |
| | { |
| | |
| | mjtNum margin = m->sensor_cutoff[i]; |
| |
|
| | |
| | mjtNum dist = margin; |
| | mjtNum fromto[6] = {0}; |
| |
|
| | |
| | int n1, id1; |
| | if (objtype == mjOBJ_BODY) { |
| | n1 = m->body_geomnum[objid]; |
| | id1 = m->body_geomadr[objid]; |
| | } else { |
| | n1 = 1; |
| | id1 = objid; |
| | } |
| | int n2, id2; |
| | if (reftype == mjOBJ_BODY) { |
| | n2 = m->body_geomnum[refid]; |
| | id2 = m->body_geomadr[refid]; |
| | } else { |
| | n2 = 1; |
| | id2 = refid; |
| | } |
| |
|
| | |
| | for (int geom1=id1; geom1 < id1+n1; geom1++) { |
| | for (int geom2=id2; geom2 < id2+n2; geom2++) { |
| | mjtNum fromto_new[6] = {0}; |
| | mjtNum dist_new = mj_geomDistance(m, d, geom1, geom2, margin, fromto_new); |
| | if (dist_new < dist) { |
| | dist = dist_new; |
| | mju_copy(fromto, fromto_new, 6); |
| | } |
| | } |
| | } |
| |
|
| | |
| | int write_sensor = 1; |
| | while (write_sensor) { |
| | |
| | if (type == mjSENS_GEOMDIST) { |
| | d->sensordata[adr] = dist; |
| | } |
| |
|
| | |
| | else if (type == mjSENS_GEOMNORMAL) { |
| | mjtNum normal[3] = {fromto[3]-fromto[0], fromto[4]-fromto[1], fromto[5]-fromto[2]}; |
| | if (normal[0] || normal[1] || normal[2]) { |
| | mju_normalize3(normal); |
| | } |
| | mju_copy3(d->sensordata + adr, normal); |
| | } |
| |
|
| | |
| | else { |
| | mju_copy(d->sensordata + adr, fromto, 6); |
| | } |
| |
|
| | |
| | if (i+1 == nsensor) { |
| | break; |
| | } |
| |
|
| | |
| | mjtSensor type_next = m->sensor_type[i+1]; |
| |
|
| | |
| | write_sensor = (type_next == mjSENS_GEOMDIST || |
| | type_next == mjSENS_GEOMNORMAL || |
| | type_next == mjSENS_GEOMFROMTO) && |
| | m->sensor_objtype[i+1] == objtype && |
| | m->sensor_objid[i+1] == objid && |
| | m->sensor_reftype[i+1] == reftype && |
| | m->sensor_refid[i+1] == refid && |
| | m->sensor_cutoff[i+1] == margin; |
| |
|
| | |
| | if (write_sensor) { |
| | i++; |
| |
|
| | |
| | adr = m->sensor_adr[i]; |
| | type = type_next; |
| | } |
| | } |
| | } |
| | break; |
| |
|
| | case mjSENS_E_POTENTIAL: |
| | mj_energyPos(m, d); |
| | d->sensordata[adr] = d->energy[0]; |
| | break; |
| |
|
| | case mjSENS_E_KINETIC: |
| | mj_energyVel(m, d); |
| | d->sensordata[adr] = d->energy[1]; |
| | break; |
| |
|
| | case mjSENS_CLOCK: |
| | d->sensordata[adr] = d->time; |
| | break; |
| |
|
| | case mjSENS_USER: |
| | nusersensor++; |
| | break; |
| |
|
| | default: |
| | mjERROR("invalid sensor type in POS stage, sensor %d", i); |
| | } |
| | } |
| | } |
| |
|
| | |
| | if (nusersensor && mjcb_sensor) { |
| | mjcb_sensor(m, d, mjSTAGE_POS); |
| | } |
| |
|
| | |
| | if (m->nplugin) { |
| | const int nslot = mjp_pluginCount(); |
| | for (int i=0; i < m->nplugin; i++) { |
| | const int slot = m->plugin[i]; |
| | const mjpPlugin* plugin = mjp_getPluginAtSlotUnsafe(slot, nslot); |
| | if (!plugin) { |
| | mjERROR("invalid plugin slot: %d", slot); |
| | } |
| | if ((plugin->capabilityflags & mjPLUGIN_SENSOR) && |
| | (plugin->needstage == mjSTAGE_POS || plugin->needstage == mjSTAGE_NONE)) { |
| | if (!plugin->compute) { |
| | mjERROR("`compute` is a null function pointer for plugin at slot %d", slot); |
| | } |
| | plugin->compute(m, d, i, mjPLUGIN_SENSOR); |
| | } |
| | } |
| | } |
| |
|
| | |
| | apply_cutoff(m, d, mjSTAGE_POS); |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mj_sensorVel(const mjModel* m, mjData* d) { |
| | int objtype, objid, reftype, refid, adr, nusersensor = 0; |
| | int ne = d->ne, nf = d->nf, nefc = d->nefc; |
| | mjtNum xvel[6]; |
| |
|
| | |
| | if (mjDISABLED(mjDSBL_SENSOR)) { |
| | return; |
| | } |
| |
|
| | |
| | int subtreeVel = 0; |
| | for (int i=0; i < m->nsensor; i++) { |
| | |
| | if (m->sensor_type[i] == mjSENS_PLUGIN) { |
| | continue; |
| | } |
| |
|
| | if (m->sensor_needstage[i] == mjSTAGE_VEL) { |
| | |
| | mjtSensor type = m->sensor_type[i]; |
| | objtype = m->sensor_objtype[i]; |
| | objid = m->sensor_objid[i]; |
| | refid = m->sensor_refid[i]; |
| | reftype = m->sensor_reftype[i]; |
| | adr = m->sensor_adr[i]; |
| |
|
| | |
| | if (subtreeVel == 0 && |
| | (type == mjSENS_SUBTREELINVEL || |
| | type == mjSENS_SUBTREEANGMOM || |
| | type == mjSENS_USER)) { |
| | |
| | mj_subtreeVel(m, d); |
| |
|
| | |
| | subtreeVel = 1; |
| | } |
| |
|
| | |
| | switch (type) { |
| | case mjSENS_VELOCIMETER: |
| | |
| | mj_objectVelocity(m, d, mjOBJ_SITE, objid, xvel, 1); |
| |
|
| | |
| | mju_copy3(d->sensordata+adr, xvel+3); |
| | break; |
| |
|
| | case mjSENS_GYRO: |
| | |
| | mj_objectVelocity(m, d, mjOBJ_SITE, objid, xvel, 1); |
| |
|
| | |
| | mju_copy3(d->sensordata+adr, xvel); |
| | break; |
| |
|
| | case mjSENS_JOINTVEL: |
| | d->sensordata[adr] = d->qvel[m->jnt_dofadr[objid]]; |
| | break; |
| |
|
| | case mjSENS_TENDONVEL: |
| | d->sensordata[adr] = d->ten_velocity[objid]; |
| | break; |
| |
|
| | case mjSENS_ACTUATORVEL: |
| | d->sensordata[adr] = d->actuator_velocity[objid]; |
| | break; |
| |
|
| | case mjSENS_BALLANGVEL: |
| | mju_copy3(d->sensordata+adr, d->qvel+m->jnt_dofadr[objid]); |
| | break; |
| |
|
| | case mjSENS_JOINTLIMITVEL: |
| | d->sensordata[adr] = 0; |
| | for (int j=ne+nf; j < nefc; j++) { |
| | if (d->efc_type[j] == mjCNSTR_LIMIT_JOINT && d->efc_id[j] == objid) { |
| | d->sensordata[adr] = d->efc_vel[j]; |
| | break; |
| | } |
| | } |
| | break; |
| |
|
| | case mjSENS_TENDONLIMITVEL: |
| | d->sensordata[adr] = 0; |
| | for (int j=ne+nf; j < nefc; j++) { |
| | if (d->efc_type[j] == mjCNSTR_LIMIT_TENDON && d->efc_id[j] == objid) { |
| | d->sensordata[adr] = d->efc_vel[j]; |
| | break; |
| | } |
| | } |
| | break; |
| |
|
| | case mjSENS_FRAMELINVEL: |
| | case mjSENS_FRAMEANGVEL: |
| | |
| | mj_objectVelocity(m, d, objtype, objid, xvel, 0); |
| |
|
| | if (refid > -1) { |
| | mjtNum *xpos, *xmat, *xpos_ref, *xmat_ref, xvel_ref[6], rel_vel[6], cross[3], rvec[3]; |
| |
|
| | |
| | get_xpos_xmat(d, objtype, objid, i, &xpos, &xmat); |
| | get_xpos_xmat(d, reftype, refid, i, &xpos_ref, &xmat_ref); |
| | mj_objectVelocity(m, d, reftype, refid, xvel_ref, 0); |
| |
|
| | |
| | mju_sub(rel_vel, xvel, xvel_ref, 6); |
| |
|
| | |
| | mju_sub3(rvec, xpos, xpos_ref); |
| | mju_cross(cross, rvec, xvel_ref); |
| | mju_addTo3(rel_vel+3, cross); |
| |
|
| | |
| | mju_mulMatTVec3(xvel, xmat_ref, rel_vel); |
| | mju_mulMatTVec3(xvel+3, xmat_ref, rel_vel+3); |
| | } |
| |
|
| | |
| | if (m->sensor_type[i] == mjSENS_FRAMELINVEL) { |
| | mju_copy3(d->sensordata+adr, xvel+3); |
| | } else { |
| | mju_copy3(d->sensordata+adr, xvel); |
| | } |
| | break; |
| |
|
| | case mjSENS_SUBTREELINVEL: |
| | mju_copy3(d->sensordata+adr, d->subtree_linvel+3*objid); |
| | break; |
| |
|
| | case mjSENS_SUBTREEANGMOM: |
| | mju_copy3(d->sensordata+adr, d->subtree_angmom+3*objid); |
| | break; |
| |
|
| | case mjSENS_USER: |
| | nusersensor++; |
| | break; |
| |
|
| | default: |
| | mjERROR("invalid type in VEL stage, sensor %d", i); |
| | } |
| | } |
| | } |
| |
|
| | |
| | if (nusersensor && mjcb_sensor) { |
| | mjcb_sensor(m, d, mjSTAGE_VEL); |
| | } |
| |
|
| | |
| | if (m->nplugin) { |
| | const int nslot = mjp_pluginCount(); |
| | for (int i=0; i < m->nplugin; i++) { |
| | const int slot = m->plugin[i]; |
| | const mjpPlugin* plugin = mjp_getPluginAtSlotUnsafe(slot, nslot); |
| | if (!plugin) { |
| | mjERROR("invalid plugin slot: %d", slot); |
| | } |
| | if ((plugin->capabilityflags & mjPLUGIN_SENSOR) && plugin->needstage == mjSTAGE_VEL) { |
| | if (!plugin->compute) { |
| | mjERROR("`compute` is null for plugin at slot %d", slot); |
| | } |
| | if (subtreeVel == 0) { |
| | |
| | |
| | mj_subtreeVel(m, d); |
| |
|
| | |
| | subtreeVel = 1; |
| | } |
| | plugin->compute(m, d, i, mjPLUGIN_SENSOR); |
| | } |
| | } |
| | } |
| |
|
| | |
| | apply_cutoff(m, d, mjSTAGE_VEL); |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mj_sensorAcc(const mjModel* m, mjData* d) { |
| | int rootid, bodyid, objtype, objid, adr, nusersensor = 0; |
| | int ne = d->ne, nf = d->nf, nefc = d->nefc, nu = m->nu; |
| | mjtNum tmp[6], conforce[6], conray[3], frc; |
| | mjContact* con; |
| |
|
| | |
| | if (mjDISABLED(mjDSBL_SENSOR)) { |
| | return; |
| | } |
| |
|
| | |
| | int rnePost = 0; |
| | for (int i=0; i < m->nsensor; i++) { |
| | |
| | if (m->sensor_type[i] == mjSENS_PLUGIN) { |
| | continue; |
| | } |
| |
|
| | if (m->sensor_needstage[i] == mjSTAGE_ACC) { |
| | |
| | mjtSensor type = m->sensor_type[i]; |
| | objtype = m->sensor_objtype[i]; |
| | objid = m->sensor_objid[i]; |
| | adr = m->sensor_adr[i]; |
| |
|
| | |
| | if (rnePost == 0 && (type == mjSENS_ACCELEROMETER || |
| | type == mjSENS_FORCE || |
| | type == mjSENS_TORQUE || |
| | type == mjSENS_FRAMELINACC || |
| | type == mjSENS_FRAMEANGACC || |
| | type == mjSENS_USER)) { |
| | |
| | mj_rnePostConstraint(m, d); |
| |
|
| | |
| | rnePost = 1; |
| | } |
| |
|
| | |
| | switch (type) { |
| | case mjSENS_TOUCH: |
| | |
| | bodyid = m->site_bodyid[objid]; |
| |
|
| | |
| | d->sensordata[adr] = 0; |
| |
|
| | |
| | for (int j=0; j < d->ncon; j++) { |
| | |
| | con = d->contact + j; |
| | int conbody[2]; |
| | for (int k=0; k < 2; k++) { |
| | conbody[k] = (con->geom[k] >= 0) ? m->geom_bodyid[con->geom[k]] : -1; |
| | } |
| |
|
| | |
| | if (con->efc_address >= 0 && (bodyid == conbody[0] || bodyid == conbody[1])) { |
| | |
| | mj_contactForce(m, d, j, conforce); |
| |
|
| | |
| | if (conforce[0] <= 0) { |
| | continue; |
| | } |
| |
|
| | |
| | mju_scl3(conray, con->frame, conforce[0]); |
| | mju_normalize3(conray); |
| |
|
| | |
| | if (bodyid == conbody[1]) { |
| | mju_scl3(conray, conray, -1); |
| | } |
| |
|
| | |
| | if (mju_rayGeom(d->site_xpos+3*objid, d->site_xmat+9*objid, |
| | m->site_size+3*objid, con->pos, conray, |
| | m->site_type[objid]) >= 0) { |
| | d->sensordata[adr] += conforce[0]; |
| | } |
| | } |
| | } |
| | break; |
| |
|
| | case mjSENS_ACCELEROMETER: |
| | |
| | mj_objectAcceleration(m, d, mjOBJ_SITE, objid, tmp, 1); |
| |
|
| | |
| | mju_copy3(d->sensordata+adr, tmp+3); |
| | break; |
| |
|
| | case mjSENS_FORCE: |
| | |
| | bodyid = m->site_bodyid[objid]; |
| | rootid = m->body_rootid[bodyid]; |
| |
|
| | |
| | mju_transformSpatial(tmp, d->cfrc_int+6*bodyid, 1, |
| | d->site_xpos+3*objid, d->subtree_com+3*rootid, d->site_xmat+9*objid); |
| |
|
| | |
| | mju_copy3(d->sensordata+adr, tmp+3); |
| | break; |
| |
|
| | case mjSENS_TORQUE: |
| | |
| | bodyid = m->site_bodyid[objid]; |
| | rootid = m->body_rootid[bodyid]; |
| |
|
| | |
| | mju_transformSpatial(tmp, d->cfrc_int+6*bodyid, 1, |
| | d->site_xpos+3*objid, d->subtree_com+3*rootid, d->site_xmat+9*objid); |
| |
|
| | |
| | mju_copy3(d->sensordata+adr, tmp); |
| | break; |
| |
|
| | case mjSENS_ACTUATORFRC: |
| | d->sensordata[adr] = d->actuator_force[objid]; |
| | break; |
| |
|
| | case mjSENS_JOINTACTFRC: |
| | d->sensordata[adr] = d->qfrc_actuator[m->jnt_dofadr[objid]]; |
| | break; |
| |
|
| | case mjSENS_TENDONACTFRC: |
| | frc = 0.0; |
| | for (int j=0; j < nu; j++) { |
| | if (m->actuator_trntype[j] == mjTRN_TENDON && m->actuator_trnid[2*j] == objid) { |
| | frc += d->actuator_force[j]; |
| | } |
| | } |
| | d->sensordata[adr] = frc; |
| | break; |
| |
|
| | case mjSENS_JOINTLIMITFRC: |
| | d->sensordata[adr] = 0; |
| | for (int j=ne+nf; j < nefc; j++) { |
| | if (d->efc_type[j] == mjCNSTR_LIMIT_JOINT && d->efc_id[j] == objid) { |
| | d->sensordata[adr] = d->efc_force[j]; |
| | break; |
| | } |
| | } |
| | break; |
| |
|
| | case mjSENS_TENDONLIMITFRC: |
| | d->sensordata[adr] = 0; |
| | for (int j=ne+nf; j < nefc; j++) { |
| | if (d->efc_type[j] == mjCNSTR_LIMIT_TENDON && d->efc_id[j] == objid) { |
| | d->sensordata[adr] = d->efc_force[j]; |
| | break; |
| | } |
| | } |
| | break; |
| |
|
| | case mjSENS_FRAMELINACC: |
| | case mjSENS_FRAMEANGACC: |
| | |
| | mj_objectAcceleration(m, d, objtype, objid, tmp, 0); |
| |
|
| | |
| | if (m->sensor_type[i] == mjSENS_FRAMELINACC) { |
| | mju_copy3(d->sensordata+adr, tmp+3); |
| | } else { |
| | mju_copy3(d->sensordata+adr, tmp); |
| | } |
| | break; |
| |
|
| | case mjSENS_USER: |
| | nusersensor++; |
| | break; |
| |
|
| | default: |
| | mjERROR("invalid type in ACC stage, sensor %d", i); |
| | } |
| | } |
| | } |
| |
|
| | |
| | if (nusersensor && mjcb_sensor) { |
| | mjcb_sensor(m, d, mjSTAGE_ACC); |
| | } |
| |
|
| | |
| | if (m->nplugin) { |
| | const int nslot = mjp_pluginCount(); |
| | for (int i=0; i < m->nplugin; i++) { |
| | const int slot = m->plugin[i]; |
| | const mjpPlugin* plugin = mjp_getPluginAtSlotUnsafe(slot, nslot); |
| | if (!plugin) { |
| | mjERROR("invalid plugin slot: %d", slot); |
| | } |
| | if ((plugin->capabilityflags & mjPLUGIN_SENSOR) && plugin->needstage == mjSTAGE_ACC) { |
| | if (!plugin->compute) { |
| | mjERROR("`compute` is null for plugin at slot %d", slot); |
| | } |
| | if (rnePost == 0) { |
| | |
| | |
| | mj_rnePostConstraint(m, d); |
| |
|
| | |
| | rnePost = 1; |
| | } |
| | plugin->compute(m, d, i, mjPLUGIN_SENSOR); |
| | } |
| | } |
| | } |
| |
|
| | |
| | apply_cutoff(m, d, mjSTAGE_ACC); |
| | } |
| |
|
| |
|
| |
|
| | |
| |
|
| | |
| | void mj_energyPos(const mjModel* m, mjData* d) { |
| | int padr; |
| | mjtNum dif[3], quat[4], stiffness; |
| |
|
| | |
| | d->energy[0] = 0; |
| | if (!mjDISABLED(mjDSBL_GRAVITY)) { |
| | for (int i=1; i < m->nbody; i++) { |
| | d->energy[0] -= m->body_mass[i] * mju_dot3(m->opt.gravity, d->xipos+3*i); |
| | } |
| | } |
| |
|
| | |
| | if (!mjDISABLED(mjDSBL_PASSIVE)) { |
| | for (int i=0; i < m->njnt; i++) { |
| | stiffness = m->jnt_stiffness[i]; |
| | padr = m->jnt_qposadr[i]; |
| |
|
| | switch ((mjtJoint) m->jnt_type[i]) { |
| | case mjJNT_FREE: |
| | mju_sub3(dif, d->qpos+padr, m->qpos_spring+padr); |
| | d->energy[0] += 0.5*stiffness*mju_dot3(dif, dif); |
| |
|
| | |
| | padr += 3; |
| | mjFALLTHROUGH; |
| |
|
| | case mjJNT_BALL: |
| | |
| | mju_copy4(quat, d->qpos+padr); |
| | mju_normalize4(quat); |
| | mju_subQuat(dif, d->qpos + padr, m->qpos_spring + padr); |
| | d->energy[0] += 0.5*stiffness*mju_dot3(dif, dif); |
| | break; |
| |
|
| | case mjJNT_SLIDE: |
| | case mjJNT_HINGE: |
| | d->energy[0] += 0.5*stiffness* |
| | (d->qpos[padr] - m->qpos_spring[padr])* |
| | (d->qpos[padr] - m->qpos_spring[padr]); |
| | break; |
| | } |
| | } |
| | } |
| |
|
| | |
| | if (!mjDISABLED(mjDSBL_PASSIVE)) { |
| | for (int i=0; i < m->ntendon; i++) { |
| | stiffness = m->tendon_stiffness[i]; |
| | mjtNum length = d->ten_length[i]; |
| | mjtNum displacement = 0; |
| |
|
| | |
| | mjtNum lower = m->tendon_lengthspring[2*i]; |
| | mjtNum upper = m->tendon_lengthspring[2*i+1]; |
| | if (length > upper) { |
| | displacement = upper - length; |
| | } else if (length < lower) { |
| | displacement = lower - length; |
| | } |
| |
|
| | d->energy[0] += 0.5*stiffness*displacement*displacement; |
| | } |
| | } |
| |
|
| | |
| | if (!mjDISABLED(mjDSBL_PASSIVE)) { |
| | for (int i=0; i < m->nflex; i++) { |
| | stiffness = m->flex_edgestiffness[i]; |
| | if (m->flex_rigid[i] || stiffness == 0 || m->flex_dim[i] > 1) { |
| | continue; |
| | } |
| |
|
| | |
| | int flex_edgeadr = m->flex_edgeadr[i]; |
| | int flex_edgenum = m->flex_edgenum[i]; |
| | for (int e=flex_edgeadr; e < flex_edgeadr+flex_edgenum; e++) { |
| | if (!m->flexedge_rigid[e]) { |
| | mjtNum displacement = m->flexedge_length0[e] - d->flexedge_length[e]; |
| | d->energy[0] += 0.5*stiffness*displacement*displacement; |
| | }; |
| | } |
| | } |
| | } |
| | } |
| |
|
| |
|
| |
|
| | |
| | void mj_energyVel(const mjModel* m, mjData* d) { |
| | mj_markStack(d); |
| | mjtNum *vec = mjSTACKALLOC(d, m->nv, mjtNum); |
| |
|
| | |
| | mj_mulM(m, d, vec, d->qvel); |
| | d->energy[1] = 0.5*mju_dot(vec, d->qvel, m->nv); |
| |
|
| | mj_freeStack(d); |
| | } |
| |
|