| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| |
|
| | #include <algorithm> |
| | #include <cstddef> |
| | #include <sstream> |
| | #include <optional> |
| |
|
| | #include <mujoco/mjplugin.h> |
| | #include <mujoco/mjtnum.h> |
| | #include <mujoco/mujoco.h> |
| | #include "cable.h" |
| |
|
| |
|
| | namespace mujoco::plugin::elasticity { |
| | namespace { |
| |
|
| | |
| | void scalar2rgba(float rgba[4], mjtNum stress[3], mjtNum vmin, mjtNum vmax) { |
| | |
| | mjtNum v = mju_norm3(stress); |
| | v = v < vmin ? vmin : v; |
| | v = v > vmax ? vmax : v; |
| | mjtNum dv = vmax - vmin; |
| |
|
| | if (v < (vmin + 0.25 * dv)) { |
| | rgba[0] = 0; |
| | rgba[1] = 4 * (v - vmin) / dv; |
| | rgba[2] = 1; |
| | } else if (v < (vmin + 0.5 * dv)) { |
| | rgba[0] = 0; |
| | rgba[1] = 1; |
| | rgba[2] = 1 + 4 * (vmin + 0.25 * dv - v) / dv; |
| | } else if (v < (vmin + 0.75 * dv)) { |
| | rgba[0] = 4 * (v - vmin - 0.5 * dv) / dv; |
| | rgba[1] = 1; |
| | rgba[2] = 0; |
| | } else { |
| | rgba[0] = 1; |
| | rgba[1] = 1 + 4 * (vmin + 0.75 * dv - v) / dv; |
| | rgba[2] = 0; |
| | } |
| | } |
| |
|
| | |
| | void QuatDiff(mjtNum* quat, const mjtNum body_quat[4], |
| | const mjtNum joint_quat[4], bool pullback = false) { |
| | if (pullback == 0) { |
| | |
| | mju_mulQuat(quat, body_quat, joint_quat); |
| | } else { |
| | |
| | mjtNum invquat[4]; |
| | mju_mulQuat(invquat, body_quat, joint_quat); |
| | mju_negQuat(quat, invquat); |
| | } |
| | } |
| |
|
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | void LocalStress(mjtNum stress[3], |
| | const mjtNum stiffness[4], |
| | const mjtNum quat[4], const mjtNum omega0[3], |
| | bool pullback = false) { |
| | mjtNum omega[3]; |
| |
|
| | |
| | mju_quat2Vel(omega, quat, 1.0); |
| |
|
| | |
| | mjtNum tmp[] = { |
| | - stiffness[0]*(omega[0] - omega0[0]) / stiffness[3], |
| | - stiffness[1]*(omega[1] - omega0[1]) / stiffness[3], |
| | - stiffness[2]*(omega[2] - omega0[2]) / stiffness[3], |
| | }; |
| |
|
| |
|
| | |
| | if (pullback) { |
| | mjtNum invquat[4]; |
| | mju_negQuat(invquat, quat); |
| | mju_rotVecQuat(stress, tmp, invquat); |
| | } else { |
| | mju_copy3(stress, tmp); |
| | } |
| | } |
| |
|
| | |
| | bool CheckAttr(const char* name, const mjModel* m, int instance) { |
| | char *end; |
| | std::string value = mj_getPluginConfig(m, instance, name); |
| | value.erase(std::remove_if(value.begin(), value.end(), isspace), value.end()); |
| | strtod(value.c_str(), &end); |
| | return end == value.data() + value.size(); |
| | } |
| |
|
| | } |
| |
|
| |
|
| | |
| | std::optional<Cable> Cable::Create( |
| | const mjModel* m, mjData* d, int instance) { |
| | if (CheckAttr("twist", m, instance) && CheckAttr("bend", m, instance)) { |
| | return Cable(m, d, instance); |
| | } else { |
| | mju_warning("Invalid parameter specification in cable plugin"); |
| | return std::nullopt; |
| | } |
| | } |
| |
|
| | |
| | Cable::Cable(const mjModel* m, mjData* d, int instance) { |
| | |
| | std::string flat = mj_getPluginConfig(m, instance, "flat"); |
| | mjtNum G = strtod(mj_getPluginConfig(m, instance, "twist"), nullptr); |
| | mjtNum E = strtod(mj_getPluginConfig(m, instance, "bend"), nullptr); |
| | vmax = strtod(mj_getPluginConfig(m, instance, "vmax"), nullptr); |
| | |
| | n = 0; |
| | for (int i = 1; i < m->nbody; i++) { |
| | if (m->body_plugin[i] == instance) { |
| | if (!n++) { |
| | i0 = i; |
| | } |
| | } |
| | } |
| |
|
| | |
| | prev.assign(n, 0); |
| | next.assign(n, 0); |
| | omega0.assign(3*n, 0); |
| | stress.assign(3*n, 0); |
| | stiffness.assign(4*n, 0); |
| |
|
| | |
| | mju_zero(d->mocap_quat, 4*m->nmocap); |
| | mju_copy(d->qpos, m->qpos0, m->nq); |
| | mj_kinematics(m, d); |
| |
|
| | |
| | for (int b = 0; b < n; b++) { |
| | int i = i0 + b; |
| | if (m->body_plugin[i] != instance) { |
| | mju_error("This body does not have the requested plugin instance"); |
| | } |
| | bool first = (b == 0), last = (b == n-1); |
| | prev[b] = first ? 0 : -1; |
| | next[b] = last ? 0 : +1; |
| |
|
| | |
| | if (prev[b] && flat != "true") { |
| | int qadr = m->jnt_qposadr[m->body_jntadr[i]] + m->body_dofnum[i]-3; |
| | mju_subQuat(omega0.data()+3*b, m->body_quat+4*i, d->qpos+qadr); |
| | } else { |
| | mju_zero3(omega0.data()+3*b); |
| | } |
| |
|
| | |
| | int geom_i = m->body_geomadr[i]; |
| | mjtNum J = 0, Iy = 0, Iz = 0; |
| | if (m->geom_type[geom_i] == mjGEOM_CYLINDER || |
| | m->geom_type[geom_i] == mjGEOM_CAPSULE) { |
| | |
| | |
| | J = mjPI * pow(m->geom_size[3*geom_i+0], 4) / 2; |
| | Iy = Iz = mjPI * pow(m->geom_size[3*geom_i+0], 4) / 4.; |
| | } else if (m->geom_type[geom_i] == mjGEOM_BOX) { |
| | |
| | |
| | mjtNum h = m->geom_size[3*geom_i+1]; |
| | mjtNum w = m->geom_size[3*geom_i+2]; |
| | mjtNum a = std::max(h, w); |
| | mjtNum b = std::min(h, w); |
| | J = a*pow(b, 3)*(16./3.-3.36*b/a*(1-pow(b, 4)/pow(a, 4)/12)); |
| | Iy = pow(2 * w, 3) * 2 * h / 12.; |
| | Iz = pow(2 * h, 3) * 2 * w / 12.; |
| | } |
| | stiffness[4*b+0] = J * G; |
| | stiffness[4*b+1] = Iy * E; |
| | stiffness[4*b+2] = Iz * E; |
| | stiffness[4*b+3] = |
| | prev[b] ? mju_dist3(d->xpos+3*i, d->xpos+3*(i+prev[b])) : 0; |
| | } |
| | } |
| |
|
| | void Cable::Compute(const mjModel* m, mjData* d, int instance) { |
| | for (int b = 0; b < n; b++) { |
| | |
| | int i = i0 + b; |
| | if (m->body_plugin[i] != instance) { |
| | mju_error( |
| | "This body is not associated with the requested plugin instance"); |
| | } |
| |
|
| | |
| | if (!stiffness[b*4+0] && !stiffness[b*4+1] && !stiffness[b*4+2]) { |
| | continue; |
| | } |
| |
|
| | |
| | mjtNum quat[4] = {0}; |
| | mjtNum lfrc[3] = {0}; |
| |
|
| | |
| | if (prev[b]) { |
| | int qadr = m->jnt_qposadr[m->body_jntadr[i]] + m->body_dofnum[i]-3; |
| | QuatDiff(quat, m->body_quat+4*i, d->qpos+qadr); |
| |
|
| | |
| | LocalStress(stress.data() + 3 * b, stiffness.data() + 4 * b, quat, |
| | omega0.data() + 3 * b, true); |
| | mju_addToScl3(lfrc, stress.data() + 3 * b, 1.0); |
| | } |
| |
|
| | if (next[b]) { |
| | int bn = b + next[b]; |
| | int in = i + next[b]; |
| |
|
| | |
| | int qadr = m->jnt_qposadr[m->body_jntadr[in]] + m->body_dofnum[in]-3; |
| | QuatDiff(quat, m->body_quat+4*in, d->qpos+qadr); |
| |
|
| | |
| | LocalStress(stress.data() + 3 * bn, stiffness.data() + 4 * bn, quat, |
| | omega0.data() + 3 * bn); |
| | mju_addToScl3(lfrc, stress.data() + 3 * bn, -1.0); |
| | } |
| |
|
| | |
| | mjtNum xfrc[3] = {0}; |
| | mju_rotVecQuat(xfrc, lfrc, d->xquat+4*i); |
| | mj_applyFT(m, d, 0, xfrc, d->xpos+3*i, i, d->qfrc_passive); |
| | } |
| | } |
| |
|
| | void Cable::Visualize(const mjModel* m, mjData* d, mjvScene* scn, |
| | int instance) { |
| | if (!vmax) { |
| | return; |
| | } |
| |
|
| | for (int b = 0; b < n; b++) { |
| | int i = i0 + b; |
| | int bn = b + next[b]; |
| |
|
| | |
| | mjtNum stress_m[3] = {0}; |
| | mjtNum *stress_l = prev[b] ? stress.data()+3*b : stress.data()+3*bn; |
| | mjtNum *stress_r = next[b] ? stress.data()+3*bn : stress.data()+3*b; |
| | mju_add3(stress_m, stress_l, stress_r); |
| | mju_scl3(stress_m, stress_m, 0.5); |
| | scalar2rgba(m->geom_rgba + 4*m->body_geomadr[i], stress_m, 0, vmax); |
| | } |
| | } |
| |
|
| | void Cable::RegisterPlugin() { |
| | mjpPlugin plugin; |
| | mjp_defaultPlugin(&plugin); |
| |
|
| | plugin.name = "mujoco.elasticity.cable"; |
| | plugin.capabilityflags |= mjPLUGIN_PASSIVE; |
| |
|
| | const char* attributes[] = {"twist", "bend", "flat", "vmax"}; |
| | plugin.nattribute = sizeof(attributes) / sizeof(attributes[0]); |
| | plugin.attributes = attributes; |
| | plugin.nstate = +[](const mjModel* m, int instance) { return 0; }; |
| |
|
| | plugin.init = +[](const mjModel* m, mjData* d, int instance) { |
| | auto elasticity_or_null = Cable::Create(m, d, instance); |
| | if (!elasticity_or_null.has_value()) { |
| | return -1; |
| | } |
| | d->plugin_data[instance] = reinterpret_cast<uintptr_t>( |
| | new Cable(std::move(*elasticity_or_null))); |
| | return 0; |
| | }; |
| | plugin.destroy = +[](mjData* d, int instance) { |
| | delete reinterpret_cast<Cable*>(d->plugin_data[instance]); |
| | d->plugin_data[instance] = 0; |
| | }; |
| | plugin.compute = |
| | +[](const mjModel* m, mjData* d, int instance, int capability_bit) { |
| | auto* elasticity = reinterpret_cast<Cable*>(d->plugin_data[instance]); |
| | elasticity->Compute(m, d, instance); |
| | }; |
| | plugin.visualize = +[](const mjModel* m, mjData* d, const mjvOption* opt, mjvScene* scn, |
| | int instance) { |
| | auto* elasticity = reinterpret_cast<Cable*>(d->plugin_data[instance]); |
| | elasticity->Visualize(m, d, scn, instance); |
| | }; |
| |
|
| | mjp_registerPlugin(&plugin); |
| | } |
| |
|
| | } |
| |
|