// Copyright 2021 DeepMind Technologies Limited // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. // You may obtain a copy of the License at // // http://www.apache.org/licenses/LICENSE-2.0 // // Unless required by applicable law or agreed to in writing, software // distributed under the License is distributed on an "AS IS" BASIS, // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. #ifndef MUJOCO_MJMODEL_H_ #define MUJOCO_MJMODEL_H_ #include #include #include // global constants #define mjPI 3.14159265358979323846 #define mjMAXVAL 1E+10 // maximum value in qpos, qvel, qacc #define mjMINMU 1E-5 // minimum friction coefficient #define mjMINIMP 0.0001 // minimum constraint impedance #define mjMAXIMP 0.9999 // maximum constraint impedance #define mjMAXCONPAIR 50 // maximum number of contacts per geom pair #define mjMAXTREEDEPTH 50 // maximum bounding volume hierarchy depth //---------------------------------- sizes --------------------------------------------------------- #define mjNEQDATA 11 // number of eq_data fields #define mjNDYN 10 // number of actuator dynamics parameters #define mjNGAIN 10 // number of actuator gain parameters #define mjNBIAS 10 // number of actuator bias parameters #define mjNFLUID 12 // number of fluid interaction parameters #define mjNREF 2 // number of solver reference parameters #define mjNIMP 5 // number of solver impedance parameters #define mjNSOLVER 200 // size of one mjData.solver array #define mjNISLAND 20 // number of mjData.solver arrays //---------------------------------- enum types (mjt) ---------------------------------------------- typedef enum mjtDisableBit_ { // disable default feature bitflags mjDSBL_CONSTRAINT = 1<<0, // entire constraint solver mjDSBL_EQUALITY = 1<<1, // equality constraints mjDSBL_FRICTIONLOSS = 1<<2, // joint and tendon frictionloss constraints mjDSBL_LIMIT = 1<<3, // joint and tendon limit constraints mjDSBL_CONTACT = 1<<4, // contact constraints mjDSBL_PASSIVE = 1<<5, // passive forces mjDSBL_GRAVITY = 1<<6, // gravitational forces mjDSBL_CLAMPCTRL = 1<<7, // clamp control to specified range mjDSBL_WARMSTART = 1<<8, // warmstart constraint solver mjDSBL_FILTERPARENT = 1<<9, // remove collisions with parent body mjDSBL_ACTUATION = 1<<10, // apply actuation forces mjDSBL_REFSAFE = 1<<11, // integrator safety: make ref[0]>=2*timestep mjDSBL_SENSOR = 1<<12, // sensors mjDSBL_MIDPHASE = 1<<13, // mid-phase collision filtering mjDSBL_EULERDAMP = 1<<14, // implicit integration of joint damping in Euler integrator mjDSBL_AUTORESET = 1<<15, // automatic reset when numerical issues are detected mjNDISABLE = 16 // number of disable flags } mjtDisableBit; typedef enum mjtEnableBit_ { // enable optional feature bitflags mjENBL_OVERRIDE = 1<<0, // override contact parameters mjENBL_ENERGY = 1<<1, // energy computation mjENBL_FWDINV = 1<<2, // record solver statistics mjENBL_INVDISCRETE = 1<<3, // discrete-time inverse dynamics // experimental features: mjENBL_MULTICCD = 1<<4, // multi-point convex collision detection mjENBL_ISLAND = 1<<5, // constraint island discovery mjENBL_NATIVECCD = 1<<6, // native convex collision detection mjNENABLE = 7 // number of enable flags } mjtEnableBit; typedef enum mjtJoint_ { // type of degree of freedom mjJNT_FREE = 0, // global position and orientation (quat) (7) mjJNT_BALL, // orientation (quat) relative to parent (4) mjJNT_SLIDE, // sliding distance along body-fixed axis (1) mjJNT_HINGE // rotation angle (rad) around body-fixed axis (1) } mjtJoint; typedef enum mjtGeom_ { // type of geometric shape // regular geom types mjGEOM_PLANE = 0, // plane mjGEOM_HFIELD, // height field mjGEOM_SPHERE, // sphere mjGEOM_CAPSULE, // capsule mjGEOM_ELLIPSOID, // ellipsoid mjGEOM_CYLINDER, // cylinder mjGEOM_BOX, // box mjGEOM_MESH, // mesh mjGEOM_SDF, // signed distance field mjNGEOMTYPES, // number of regular geom types // rendering-only geom types: not used in mjModel, not counted in mjNGEOMTYPES mjGEOM_ARROW = 100, // arrow mjGEOM_ARROW1, // arrow without wedges mjGEOM_ARROW2, // arrow in both directions mjGEOM_LINE, // line mjGEOM_LINEBOX, // box with line edges mjGEOM_FLEX, // flex mjGEOM_SKIN, // skin mjGEOM_LABEL, // text label mjGEOM_TRIANGLE, // triangle mjGEOM_NONE = 1001 // missing geom type } mjtGeom; typedef enum mjtCamLight_ { // tracking mode for camera and light mjCAMLIGHT_FIXED = 0, // pos and rot fixed in body mjCAMLIGHT_TRACK, // pos tracks body, rot fixed in global mjCAMLIGHT_TRACKCOM, // pos tracks subtree com, rot fixed in body mjCAMLIGHT_TARGETBODY, // pos fixed in body, rot tracks target body mjCAMLIGHT_TARGETBODYCOM // pos fixed in body, rot tracks target subtree com } mjtCamLight; typedef enum mjtTexture_ { // type of texture mjTEXTURE_2D = 0, // 2d texture, suitable for planes and hfields mjTEXTURE_CUBE, // cube texture, suitable for all other geom types mjTEXTURE_SKYBOX // cube texture used as skybox } mjtTexture; typedef enum mjtTextureRole_ { // role of texture map in rendering mjTEXROLE_USER = 0, // unspecified mjTEXROLE_RGB, // base color (albedo) mjTEXROLE_OCCLUSION, // ambient occlusion mjTEXROLE_ROUGHNESS, // roughness mjTEXROLE_METALLIC, // metallic mjTEXROLE_NORMAL, // normal (bump) map mjTEXROLE_OPACITY, // transperancy mjTEXROLE_EMISSIVE, // light emission mjTEXROLE_RGBA, // base color, opacity mjTEXROLE_ORM, // occlusion, roughness, metallic mjNTEXROLE } mjtTextureRole; typedef enum mjtIntegrator_ { // integrator mode mjINT_EULER = 0, // semi-implicit Euler mjINT_RK4, // 4th-order Runge Kutta mjINT_IMPLICIT, // implicit in velocity mjINT_IMPLICITFAST // implicit in velocity, no rne derivative } mjtIntegrator; typedef enum mjtCone_ { // type of friction cone mjCONE_PYRAMIDAL = 0, // pyramidal mjCONE_ELLIPTIC // elliptic } mjtCone; typedef enum mjtJacobian_ { // type of constraint Jacobian mjJAC_DENSE = 0, // dense mjJAC_SPARSE, // sparse mjJAC_AUTO // dense if nv<60, sparse otherwise } mjtJacobian; typedef enum mjtSolver_ { // constraint solver algorithm mjSOL_PGS = 0, // PGS (dual) mjSOL_CG, // CG (primal) mjSOL_NEWTON // Newton (primal) } mjtSolver; typedef enum mjtEq_ { // type of equality constraint mjEQ_CONNECT = 0, // connect two bodies at a point (ball joint) mjEQ_WELD, // fix relative position and orientation of two bodies mjEQ_JOINT, // couple the values of two scalar joints with cubic mjEQ_TENDON, // couple the lengths of two tendons with cubic mjEQ_FLEX, // fix all edge lengths of a flex mjEQ_DISTANCE // unsupported, will cause an error if used } mjtEq; typedef enum mjtWrap_ { // type of tendon wrap object mjWRAP_NONE = 0, // null object mjWRAP_JOINT, // constant moment arm mjWRAP_PULLEY, // pulley used to split tendon mjWRAP_SITE, // pass through site mjWRAP_SPHERE, // wrap around sphere mjWRAP_CYLINDER // wrap around (infinite) cylinder } mjtWrap; typedef enum mjtTrn_ { // type of actuator transmission mjTRN_JOINT = 0, // force on joint mjTRN_JOINTINPARENT, // force on joint, expressed in parent frame mjTRN_SLIDERCRANK, // force via slider-crank linkage mjTRN_TENDON, // force on tendon mjTRN_SITE, // force on site mjTRN_BODY, // adhesion force on a body's geoms mjTRN_UNDEFINED = 1000 // undefined transmission type } mjtTrn; typedef enum mjtDyn_ { // type of actuator dynamics mjDYN_NONE = 0, // no internal dynamics; ctrl specifies force mjDYN_INTEGRATOR, // integrator: da/dt = u mjDYN_FILTER, // linear filter: da/dt = (u-a) / tau mjDYN_FILTEREXACT, // linear filter: da/dt = (u-a) / tau, with exact integration mjDYN_MUSCLE, // piece-wise linear filter with two time constants mjDYN_USER // user-defined dynamics type } mjtDyn; typedef enum mjtGain_ { // type of actuator gain mjGAIN_FIXED = 0, // fixed gain mjGAIN_AFFINE, // const + kp*length + kv*velocity mjGAIN_MUSCLE, // muscle FLV curve computed by mju_muscleGain() mjGAIN_USER // user-defined gain type } mjtGain; typedef enum mjtBias_ { // type of actuator bias mjBIAS_NONE = 0, // no bias mjBIAS_AFFINE, // const + kp*length + kv*velocity mjBIAS_MUSCLE, // muscle passive force computed by mju_muscleBias() mjBIAS_USER // user-defined bias type } mjtBias; typedef enum mjtObj_ { // type of MujoCo object mjOBJ_UNKNOWN = 0, // unknown object type mjOBJ_BODY, // body mjOBJ_XBODY, // body, used to access regular frame instead of i-frame mjOBJ_JOINT, // joint mjOBJ_DOF, // dof mjOBJ_GEOM, // geom mjOBJ_SITE, // site mjOBJ_CAMERA, // camera mjOBJ_LIGHT, // light mjOBJ_FLEX, // flex mjOBJ_MESH, // mesh mjOBJ_SKIN, // skin mjOBJ_HFIELD, // heightfield mjOBJ_TEXTURE, // texture mjOBJ_MATERIAL, // material for rendering mjOBJ_PAIR, // geom pair to include mjOBJ_EXCLUDE, // body pair to exclude mjOBJ_EQUALITY, // equality constraint mjOBJ_TENDON, // tendon mjOBJ_ACTUATOR, // actuator mjOBJ_SENSOR, // sensor mjOBJ_NUMERIC, // numeric mjOBJ_TEXT, // text mjOBJ_TUPLE, // tuple mjOBJ_KEY, // keyframe mjOBJ_PLUGIN, // plugin instance mjNOBJECT, // number of object types // meta elements, do not appear in mjModel mjOBJ_FRAME = 100 // frame } mjtObj; typedef enum mjtConstraint_ { // type of constraint mjCNSTR_EQUALITY = 0, // equality constraint mjCNSTR_FRICTION_DOF, // dof friction mjCNSTR_FRICTION_TENDON, // tendon friction mjCNSTR_LIMIT_JOINT, // joint limit mjCNSTR_LIMIT_TENDON, // tendon limit mjCNSTR_CONTACT_FRICTIONLESS, // frictionless contact mjCNSTR_CONTACT_PYRAMIDAL, // frictional contact, pyramidal friction cone mjCNSTR_CONTACT_ELLIPTIC // frictional contact, elliptic friction cone } mjtConstraint; typedef enum mjtConstraintState_ { // constraint state mjCNSTRSTATE_SATISFIED = 0, // constraint satisfied, zero cost (limit, contact) mjCNSTRSTATE_QUADRATIC, // quadratic cost (equality, friction, limit, contact) mjCNSTRSTATE_LINEARNEG, // linear cost, negative side (friction) mjCNSTRSTATE_LINEARPOS, // linear cost, positive side (friction) mjCNSTRSTATE_CONE // squared distance to cone cost (elliptic contact) } mjtConstraintState; typedef enum mjtSensor_ { // type of sensor // common robotic sensors, attached to a site mjSENS_TOUCH = 0, // scalar contact normal forces summed over sensor zone mjSENS_ACCELEROMETER, // 3D linear acceleration, in local frame mjSENS_VELOCIMETER, // 3D linear velocity, in local frame mjSENS_GYRO, // 3D angular velocity, in local frame mjSENS_FORCE, // 3D force between site's body and its parent body mjSENS_TORQUE, // 3D torque between site's body and its parent body mjSENS_MAGNETOMETER, // 3D magnetometer mjSENS_RANGEFINDER, // scalar distance to nearest geom or site along z-axis mjSENS_CAMPROJECTION, // pixel coordinates of a site in the camera image // sensors related to scalar joints, tendons, actuators mjSENS_JOINTPOS, // scalar joint position (hinge and slide only) mjSENS_JOINTVEL, // scalar joint velocity (hinge and slide only) mjSENS_TENDONPOS, // scalar tendon position mjSENS_TENDONVEL, // scalar tendon velocity mjSENS_ACTUATORPOS, // scalar actuator position mjSENS_ACTUATORVEL, // scalar actuator velocity mjSENS_ACTUATORFRC, // scalar actuator force mjSENS_JOINTACTFRC, // scalar actuator force, measured at the joint // sensors related to ball joints mjSENS_BALLQUAT, // 4D ball joint quaternion mjSENS_BALLANGVEL, // 3D ball joint angular velocity // joint and tendon limit sensors, in constraint space mjSENS_JOINTLIMITPOS, // joint limit distance-margin mjSENS_JOINTLIMITVEL, // joint limit velocity mjSENS_JOINTLIMITFRC, // joint limit force mjSENS_TENDONLIMITPOS, // tendon limit distance-margin mjSENS_TENDONLIMITVEL, // tendon limit velocity mjSENS_TENDONLIMITFRC, // tendon limit force // sensors attached to an object with spatial frame: (x)body, geom, site, camera mjSENS_FRAMEPOS, // 3D position mjSENS_FRAMEQUAT, // 4D unit quaternion orientation mjSENS_FRAMEXAXIS, // 3D unit vector: x-axis of object's frame mjSENS_FRAMEYAXIS, // 3D unit vector: y-axis of object's frame mjSENS_FRAMEZAXIS, // 3D unit vector: z-axis of object's frame mjSENS_FRAMELINVEL, // 3D linear velocity mjSENS_FRAMEANGVEL, // 3D angular velocity mjSENS_FRAMELINACC, // 3D linear acceleration mjSENS_FRAMEANGACC, // 3D angular acceleration // sensors related to kinematic subtrees; attached to a body (which is the subtree root) mjSENS_SUBTREECOM, // 3D center of mass of subtree mjSENS_SUBTREELINVEL, // 3D linear velocity of subtree mjSENS_SUBTREEANGMOM, // 3D angular momentum of subtree // sensors for geometric distance; attached to geoms or bodies mjSENS_GEOMDIST, // signed distance between two geoms mjSENS_GEOMNORMAL, // normal direction between two geoms mjSENS_GEOMFROMTO, // segment between two geoms // global sensors mjSENS_CLOCK, // simulation time // plugin-controlled sensors mjSENS_PLUGIN, // plugin-controlled // user-defined sensor mjSENS_USER // sensor data provided by mjcb_sensor callback } mjtSensor; typedef enum mjtStage_ { // computation stage mjSTAGE_NONE = 0, // no computations mjSTAGE_POS, // position-dependent computations mjSTAGE_VEL, // velocity-dependent computations mjSTAGE_ACC // acceleration/force-dependent computations } mjtStage; typedef enum mjtDataType_ { // data type for sensors mjDATATYPE_REAL = 0, // real values, no constraints mjDATATYPE_POSITIVE, // positive values; 0 or negative: inactive mjDATATYPE_AXIS, // 3D unit vector mjDATATYPE_QUATERNION // unit quaternion } mjtDataType; typedef enum mjtSameFrame_ { // frame alignment of bodies with their children mjSAMEFRAME_NONE = 0, // no alignment mjSAMEFRAME_BODY, // frame is same as body frame mjSAMEFRAME_INERTIA, // frame is same as inertial frame mjSAMEFRAME_BODYROT, // frame orientation is same as body orientation mjSAMEFRAME_INERTIAROT // frame orientation is same as inertia orientation } mjtSameFrame; typedef enum mjtLRMode_ { // mode for actuator length range computation mjLRMODE_NONE = 0, // do not process any actuators mjLRMODE_MUSCLE, // process muscle actuators mjLRMODE_MUSCLEUSER, // process muscle and user actuators mjLRMODE_ALL // process all actuators } mjtLRMode; typedef enum mjtFlexSelf_ { // mode for flex selfcollide mjFLEXSELF_NONE = 0, // no self-collisions mjFLEXSELF_NARROW, // skip midphase, go directly to narrowphase mjFLEXSELF_BVH, // use BVH in midphase (if midphase enabled) mjFLEXSELF_SAP, // use SAP in midphase mjFLEXSELF_AUTO // choose between BVH and SAP automatically } mjtFlexSelf; //---------------------------------- mjLROpt ------------------------------------------------------- struct mjLROpt_ { // options for mj_setLengthRange() // flags int mode; // which actuators to process (mjtLRMode) int useexisting; // use existing length range if available int uselimit; // use joint and tendon limits if available // algorithm parameters mjtNum accel; // target acceleration used to compute force mjtNum maxforce; // maximum force; 0: no limit mjtNum timeconst; // time constant for velocity reduction; min 0.01 mjtNum timestep; // simulation timestep; 0: use mjOption.timestep mjtNum inttotal; // total simulation time interval mjtNum interval; // evaluation time interval (at the end) mjtNum tolrange; // convergence tolerance (relative to range) }; typedef struct mjLROpt_ mjLROpt; //---------------------------------- mjVFS --------------------------------------------------------- struct mjVFS_ { // virtual file system for loading from memory void* impl_; // internal pointer to VFS memory }; typedef struct mjVFS_ mjVFS; //---------------------------------- mjOption ------------------------------------------------------ struct mjOption_ { // physics options // timing parameters mjtNum timestep; // timestep mjtNum apirate; // update rate for remote API (Hz) // solver parameters mjtNum impratio; // ratio of friction-to-normal contact impedance mjtNum tolerance; // main solver tolerance mjtNum ls_tolerance; // CG/Newton linesearch tolerance mjtNum noslip_tolerance; // noslip solver tolerance mjtNum ccd_tolerance; // convex collision solver tolerance // physical constants mjtNum gravity[3]; // gravitational acceleration mjtNum wind[3]; // wind (for lift, drag and viscosity) mjtNum magnetic[3]; // global magnetic flux mjtNum density; // density of medium mjtNum viscosity; // viscosity of medium // override contact solver parameters (if enabled) mjtNum o_margin; // margin mjtNum o_solref[mjNREF]; // solref mjtNum o_solimp[mjNIMP]; // solimp mjtNum o_friction[5]; // friction // discrete settings int integrator; // integration mode (mjtIntegrator) int cone; // type of friction cone (mjtCone) int jacobian; // type of Jacobian (mjtJacobian) int solver; // solver algorithm (mjtSolver) int iterations; // maximum number of main solver iterations int ls_iterations; // maximum number of CG/Newton linesearch iterations int noslip_iterations; // maximum number of noslip solver iterations int ccd_iterations; // maximum number of convex collision solver iterations int disableflags; // bit flags for disabling standard features int enableflags; // bit flags for enabling optional features int disableactuator; // bit flags for disabling actuators by group id // sdf collision settings int sdf_initpoints; // number of starting points for gradient descent int sdf_iterations; // max number of iterations for gradient descent }; typedef struct mjOption_ mjOption; //---------------------------------- mjVisual ------------------------------------------------------ struct mjVisual_ { // visualization options struct { // global parameters int orthographic; // is the free camera orthographic (0: no, 1: yes) float fovy; // y field-of-view of free camera (orthographic ? length : degree) float ipd; // inter-pupilary distance for free camera float azimuth; // initial azimuth of free camera (degrees) float elevation; // initial elevation of free camera (degrees) float linewidth; // line width for wireframe and ray rendering float glow; // glow coefficient for selected body float realtime; // initial real-time factor (1: real time) int offwidth; // width of offscreen buffer int offheight; // height of offscreen buffer int ellipsoidinertia; // geom for inertia visualization (0: box, 1: ellipsoid) int bvactive; // visualize active bounding volumes (0: no, 1: yes) } global; struct { // rendering quality int shadowsize; // size of shadowmap texture int offsamples; // number of multisamples for offscreen rendering int numslices; // number of slices for builtin geom drawing int numstacks; // number of stacks for builtin geom drawing int numquads; // number of quads for box rendering } quality; struct { // head light float ambient[3]; // ambient rgb (alpha=1) float diffuse[3]; // diffuse rgb (alpha=1) float specular[3]; // specular rgb (alpha=1) int active; // is headlight active } headlight; struct { // mapping float stiffness; // mouse perturbation stiffness (space->force) float stiffnessrot; // mouse perturbation stiffness (space->torque) float force; // from force units to space units float torque; // from torque units to space units float alpha; // scale geom alphas when transparency is enabled float fogstart; // OpenGL fog starts at fogstart * mjModel.stat.extent float fogend; // OpenGL fog ends at fogend * mjModel.stat.extent float znear; // near clipping plane = znear * mjModel.stat.extent float zfar; // far clipping plane = zfar * mjModel.stat.extent float haze; // haze ratio float shadowclip; // directional light: shadowclip * mjModel.stat.extent float shadowscale; // spot light: shadowscale * light.cutoff float actuatortendon; // scale tendon width } map; struct { // scale of decor elements relative to mean body size float forcewidth; // width of force arrow float contactwidth; // contact width float contactheight; // contact height float connect; // autoconnect capsule width float com; // com radius float camera; // camera object float light; // light object float selectpoint; // selection point float jointlength; // joint length float jointwidth; // joint width float actuatorlength; // actuator length float actuatorwidth; // actuator width float framelength; // bodyframe axis length float framewidth; // bodyframe axis width float constraint; // constraint width float slidercrank; // slidercrank width float frustum; // frustum zfar plane } scale; struct { // color of decor elements float fog[4]; // fog float haze[4]; // haze float force[4]; // external force float inertia[4]; // inertia box float joint[4]; // joint float actuator[4]; // actuator, neutral float actuatornegative[4]; // actuator, negative limit float actuatorpositive[4]; // actuator, positive limit float com[4]; // center of mass float camera[4]; // camera object float light[4]; // light object float selectpoint[4]; // selection point float connect[4]; // auto connect float contactpoint[4]; // contact point float contactforce[4]; // contact force float contactfriction[4]; // contact friction force float contacttorque[4]; // contact torque float contactgap[4]; // contact point in gap float rangefinder[4]; // rangefinder ray float constraint[4]; // constraint float slidercrank[4]; // slidercrank float crankbroken[4]; // used when crank must be stretched/broken float frustum[4]; // camera frustum float bv[4]; // bounding volume float bvactive[4]; // active bounding volume } rgba; }; typedef struct mjVisual_ mjVisual; //---------------------------------- mjStatistic --------------------------------------------------- struct mjStatistic_ { // model statistics (in qpos0) mjtNum meaninertia; // mean diagonal inertia mjtNum meanmass; // mean body mass mjtNum meansize; // mean body size mjtNum extent; // spatial extent mjtNum center[3]; // center of model }; typedef struct mjStatistic_ mjStatistic; //---------------------------------- mjModel ------------------------------------------------------- struct mjModel_ { // ------------------------------- sizes // sizes needed at mjModel construction int nq; // number of generalized coordinates = dim(qpos) int nv; // number of degrees of freedom = dim(qvel) int nu; // number of actuators/controls = dim(ctrl) int na; // number of activation states = dim(act) int nbody; // number of bodies int nbvh; // number of total bounding volumes in all bodies int nbvhstatic; // number of static bounding volumes (aabb stored in mjModel) int nbvhdynamic; // number of dynamic bounding volumes (aabb stored in mjData) int njnt; // number of joints int ngeom; // number of geoms int nsite; // number of sites int ncam; // number of cameras int nlight; // number of lights int nflex; // number of flexes int nflexvert; // number of vertices in all flexes int nflexedge; // number of edges in all flexes int nflexelem; // number of elements in all flexes int nflexelemdata; // number of element vertex ids in all flexes int nflexelemedge; // number of element edge ids in all flexes int nflexshelldata; // number of shell fragment vertex ids in all flexes int nflexevpair; // number of element-vertex pairs in all flexes int nflextexcoord; // number of vertices with texture coordinates int nmesh; // number of meshes int nmeshvert; // number of vertices in all meshes int nmeshnormal; // number of normals in all meshes int nmeshtexcoord; // number of texcoords in all meshes int nmeshface; // number of triangular faces in all meshes int nmeshgraph; // number of ints in mesh auxiliary data int nskin; // number of skins int nskinvert; // number of vertices in all skins int nskintexvert; // number of vertiex with texcoords in all skins int nskinface; // number of triangular faces in all skins int nskinbone; // number of bones in all skins int nskinbonevert; // number of vertices in all skin bones int nhfield; // number of heightfields int nhfielddata; // number of data points in all heightfields int ntex; // number of textures int ntexdata; // number of bytes in texture rgb data int nmat; // number of materials int npair; // number of predefined geom pairs int nexclude; // number of excluded geom pairs int neq; // number of equality constraints int ntendon; // number of tendons int nwrap; // number of wrap objects in all tendon paths int nsensor; // number of sensors int nnumeric; // number of numeric custom fields int nnumericdata; // number of mjtNums in all numeric fields int ntext; // number of text custom fields int ntextdata; // number of mjtBytes in all text fields int ntuple; // number of tuple custom fields int ntupledata; // number of objects in all tuple fields int nkey; // number of keyframes int nmocap; // number of mocap bodies int nplugin; // number of plugin instances int npluginattr; // number of chars in all plugin config attributes int nuser_body; // number of mjtNums in body_user int nuser_jnt; // number of mjtNums in jnt_user int nuser_geom; // number of mjtNums in geom_user int nuser_site; // number of mjtNums in site_user int nuser_cam; // number of mjtNums in cam_user int nuser_tendon; // number of mjtNums in tendon_user int nuser_actuator; // number of mjtNums in actuator_user int nuser_sensor; // number of mjtNums in sensor_user int nnames; // number of chars in all names int npaths; // number of chars in all paths // sizes set after mjModel construction int nnames_map; // number of slots in the names hash map int nM; // number of non-zeros in sparse inertia matrix int nB; // number of non-zeros in sparse body-dof matrix int nC; // number of non-zeros in sparse reduced dof-dof matrix int nD; // number of non-zeros in sparse dof-dof matrix int nJmom; // number of non-zeros in sparse actuator_moment matrix int ntree; // number of kinematic trees under world body int ngravcomp; // number of bodies with nonzero gravcomp int nemax; // number of potential equality-constraint rows int njmax; // number of available rows in constraint Jacobian (legacy) int nconmax; // number of potential contacts in contact list (legacy) int nuserdata; // number of mjtNums reserved for the user int nsensordata; // number of mjtNums in sensor data vector int npluginstate; // number of mjtNums in plugin state vector size_t narena; // number of bytes in the mjData arena (inclusive of stack) size_t nbuffer; // number of bytes in buffer // ------------------------------- options and statistics mjOption opt; // physics options mjVisual vis; // visualization options mjStatistic stat; // model statistics // ------------------------------- buffers // main buffer void* buffer; // main buffer; all pointers point in it (nbuffer) // default generalized coordinates mjtNum* qpos0; // qpos values at default pose (nq x 1) mjtNum* qpos_spring; // reference pose for springs (nq x 1) // bodies int* body_parentid; // id of body's parent (nbody x 1) int* body_rootid; // id of root above body (nbody x 1) int* body_weldid; // id of body that this body is welded to (nbody x 1) int* body_mocapid; // id of mocap data; -1: none (nbody x 1) int* body_jntnum; // number of joints for this body (nbody x 1) int* body_jntadr; // start addr of joints; -1: no joints (nbody x 1) int* body_dofnum; // number of motion degrees of freedom (nbody x 1) int* body_dofadr; // start addr of dofs; -1: no dofs (nbody x 1) int* body_treeid; // id of body's kinematic tree; -1: static (nbody x 1) int* body_geomnum; // number of geoms (nbody x 1) int* body_geomadr; // start addr of geoms; -1: no geoms (nbody x 1) mjtByte* body_simple; // 1: diag M; 2: diag M, sliders only (nbody x 1) mjtByte* body_sameframe; // same frame as inertia (mjtSameframe) (nbody x 1) mjtNum* body_pos; // position offset rel. to parent body (nbody x 3) mjtNum* body_quat; // orientation offset rel. to parent body (nbody x 4) mjtNum* body_ipos; // local position of center of mass (nbody x 3) mjtNum* body_iquat; // local orientation of inertia ellipsoid (nbody x 4) mjtNum* body_mass; // mass (nbody x 1) mjtNum* body_subtreemass; // mass of subtree starting at this body (nbody x 1) mjtNum* body_inertia; // diagonal inertia in ipos/iquat frame (nbody x 3) mjtNum* body_invweight0; // mean inv inert in qpos0 (trn, rot) (nbody x 2) mjtNum* body_gravcomp; // antigravity force, units of body weight (nbody x 1) mjtNum* body_margin; // MAX over all geom margins (nbody x 1) mjtNum* body_user; // user data (nbody x nuser_body) int* body_plugin; // plugin instance id; -1: not in use (nbody x 1) int* body_contype; // OR over all geom contypes (nbody x 1) int* body_conaffinity; // OR over all geom conaffinities (nbody x 1) int* body_bvhadr; // address of bvh root (nbody x 1) int* body_bvhnum; // number of bounding volumes (nbody x 1) // bounding volume hierarchy int* bvh_depth; // depth in the bounding volume hierarchy (nbvh x 1) int* bvh_child; // left and right children in tree (nbvh x 2) int* bvh_nodeid; // geom or elem id of node; -1: non-leaf (nbvh x 1) mjtNum* bvh_aabb; // local bounding box (center, size) (nbvhstatic x 6) // joints int* jnt_type; // type of joint (mjtJoint) (njnt x 1) int* jnt_qposadr; // start addr in 'qpos' for joint's data (njnt x 1) int* jnt_dofadr; // start addr in 'qvel' for joint's data (njnt x 1) int* jnt_bodyid; // id of joint's body (njnt x 1) int* jnt_group; // group for visibility (njnt x 1) mjtByte* jnt_limited; // does joint have limits (njnt x 1) mjtByte* jnt_actfrclimited; // does joint have actuator force limits (njnt x 1) mjtByte* jnt_actgravcomp; // is gravcomp force applied via actuators (njnt x 1) mjtNum* jnt_solref; // constraint solver reference: limit (njnt x mjNREF) mjtNum* jnt_solimp; // constraint solver impedance: limit (njnt x mjNIMP) mjtNum* jnt_pos; // local anchor position (njnt x 3) mjtNum* jnt_axis; // local joint axis (njnt x 3) mjtNum* jnt_stiffness; // stiffness coefficient (njnt x 1) mjtNum* jnt_range; // joint limits (njnt x 2) mjtNum* jnt_actfrcrange; // range of total actuator force (njnt x 2) mjtNum* jnt_margin; // min distance for limit detection (njnt x 1) mjtNum* jnt_user; // user data (njnt x nuser_jnt) // dofs int* dof_bodyid; // id of dof's body (nv x 1) int* dof_jntid; // id of dof's joint (nv x 1) int* dof_parentid; // id of dof's parent; -1: none (nv x 1) int* dof_treeid; // id of dof's kinematic tree (nv x 1) int* dof_Madr; // dof address in M-diagonal (nv x 1) int* dof_simplenum; // number of consecutive simple dofs (nv x 1) mjtNum* dof_solref; // constraint solver reference:frictionloss (nv x mjNREF) mjtNum* dof_solimp; // constraint solver impedance:frictionloss (nv x mjNIMP) mjtNum* dof_frictionloss; // dof friction loss (nv x 1) mjtNum* dof_armature; // dof armature inertia/mass (nv x 1) mjtNum* dof_damping; // damping coefficient (nv x 1) mjtNum* dof_invweight0; // diag. inverse inertia in qpos0 (nv x 1) mjtNum* dof_M0; // diag. inertia in qpos0 (nv x 1) // geoms int* geom_type; // geometric type (mjtGeom) (ngeom x 1) int* geom_contype; // geom contact type (ngeom x 1) int* geom_conaffinity; // geom contact affinity (ngeom x 1) int* geom_condim; // contact dimensionality (1, 3, 4, 6) (ngeom x 1) int* geom_bodyid; // id of geom's body (ngeom x 1) int* geom_dataid; // id of geom's mesh/hfield; -1: none (ngeom x 1) int* geom_matid; // material id for rendering; -1: none (ngeom x 1) int* geom_group; // group for visibility (ngeom x 1) int* geom_priority; // geom contact priority (ngeom x 1) int* geom_plugin; // plugin instance id; -1: not in use (ngeom x 1) mjtByte* geom_sameframe; // same frame as body (mjtSameframe) (ngeom x 1) mjtNum* geom_solmix; // mixing coef for solref/imp in geom pair (ngeom x 1) mjtNum* geom_solref; // constraint solver reference: contact (ngeom x mjNREF) mjtNum* geom_solimp; // constraint solver impedance: contact (ngeom x mjNIMP) mjtNum* geom_size; // geom-specific size parameters (ngeom x 3) mjtNum* geom_aabb; // bounding box, (center, size) (ngeom x 6) mjtNum* geom_rbound; // radius of bounding sphere (ngeom x 1) mjtNum* geom_pos; // local position offset rel. to body (ngeom x 3) mjtNum* geom_spos; // spec local position offset rel. to body (ngeom x 3) mjtNum* geom_quat; // local orientation offset rel. to body (ngeom x 4) mjtNum* geom_squat; // spec local orientation offset rel. body (ngeom x 4) mjtNum* geom_friction; // friction for (slide, spin, roll) (ngeom x 3) mjtNum* geom_margin; // detect contact if dist