Mujoco核心数据结构-mjData mjModel

Defined in mjdata.h
This is the data structure holding information about one solver iteration. mjData.solver is a preallocated array of mjSolverStat data structures, one for each iteration of the solver, up to a maximum of mjNSOLVER. The actual number of solver iterations is given by mjData.solver_iter.

struct _mjData
{
    // constant sizes
    int nstack;                     // number of mjtNums that can fit in stack
    int nbuffer;                    // size of main buffer in bytes

    // stack pointer
    int pstack;                     // first available mjtNum address in stack

    // memory utilization stats
    int maxuse_stack;               // maximum stack allocation
    int maxuse_con;                 // maximum number of contacts
    int maxuse_efc;                 // maximum number of scalar constraints

    // diagnostics
    mjWarningStat warning[mjNWARNING]; // warning statistics
    mjTimerStat timer[mjNTIMER];       // timer statistics
    mjSolverStat solver[mjNSOLVER];    // solver statistics per iteration
    int solver_iter;                // number of solver iterations
    int solver_nnz;                 // number of non-zeros in Hessian or efc_AR
    mjtNum solver_fwdinv[2];        // forward-inverse comparison: qfrc, efc

    // variable sizes
    int ne;                         // number of equality constraints
    int nf;                         // number of friction constraints
    int nefc;                       // number of constraints
    int ncon;                       // number of detected contacts

    // global properties
    mjtNum time;                    // simulation time
    mjtNum energy[2];               // potential, kinetic energy

    //-------------------------------- end of info header

    // buffers
    void*     buffer;               // main buffer; all pointers point in it    (nbuffer bytes)
    mjtNum*   stack;                // stack buffer                             (nstack mjtNums)

    //-------------------------------- main inputs and outputs of the computation

    // state
    mjtNum*   qpos;                 // position                                 (nq x 1)
    mjtNum*   qvel;                 // velocity                                 (nv x 1)
    mjtNum*   act;                  // actuator activation                      (na x 1)
    mjtNum*   qacc_warmstart;       // acceleration used for warmstart          (nv x 1)

    // control
    //0 = torque actuator,1=position servo,2= velocity servo
    mjtNum*   ctrl;                 // control                                  (nu x 1)
    mjtNum*   qfrc_applied;         // applied ge`neralized force`                (nv x 1)
    mjtNum*   xfrc_applied;         // applied Cartesian force/torque           (nbody x 6)

    // dynamics
    //M*qacc + qfrc_bias = qfrc_applied + ctrl中的qacc,加速度
    mjtNum*   qacc;                 // acceleration                             (nv x 1)
    mjtNum*   act_dot;              // time-derivative of actuator activation   (na x 1)

    // mocap data
    mjtNum*  mocap_pos;             // positions of mocap bodies                (nmocap x 3)
    mjtNum*  mocap_quat;            // orientations of mocap bodies             (nmocap x 4)

    // user data
    mjtNum*  userdata;              // user data, not touched by engine         (nuserdata x 1)

    // sensors
    //传感器是3x1,即一个传感器就有3个数据x,y,z,如果感应的是速度,则是dx,dy,dz
    //传感器类型:framepos=感应位置,framelinvel感应速度
    mjtNum*  sensordata;            // sensor data array                        (nsensordata x 1)

    //-------------------------------- POSITION dependent

    // computed by mj_fwdPosition/mj_kinematics
    mjtNum*   xpos;                 // Cartesian position of body frame         (nbody x 3)
    mjtNum*   xquat;                // Cartesian orientation of body frame      (nbody x 4)
    mjtNum*   xmat;                 // Cartesian orientation of body frame      (nbody x 9)
    mjtNum*   xipos;                // Cartesian position of body com           (nbody x 3)
    mjtNum*   ximat;                // Cartesian orientation of body inertia    (nbody x 9)
    mjtNum*   xanchor;              // Cartesian position of joint anchor       (njnt x 3)
    mjtNum*   xaxis;                // Cartesian joint axis                     (njnt x 3)
    mjtNum*   geom_xpos;            // Cartesian geom position                  (ngeom x 3)
    mjtNum*   geom_xmat;            // Cartesian geom orientation               (ngeom x 9)
    mjtNum*   site_xpos;            // Cartesian site position                  (nsite x 3)
    mjtNum*   site_xmat;            // Cartesian site orientation               (nsite x 9)
    mjtNum*   cam_xpos;             // Cartesian camera position                (ncam x 3)
    mjtNum*   cam_xmat;             // Cartesian camera orientation             (ncam x 9)
    mjtNum*   light_xpos;           // Cartesian light position                 (nlight x 3)
    mjtNum*   light_xdir;           // Cartesian light direction                (nlight x 3)

    // computed by mj_fwdPosition/mj_comPos
    mjtNum*   subtree_com;          // center of mass of each subtree           (nbody x 3)
    mjtNum*   cdof;                 // com-based motion axis of each dof        (nv x 6)
    mjtNum*   cinert;               // com-based body inertia and mass          (nbody x 10)

    // computed by mj_fwdPosition/mj_tendon
    int*      ten_wrapadr;          // start address of tendon's path           (ntendon x 1)
    int*      ten_wrapnum;          // number of wrap points in path            (ntendon x 1)
    int*      ten_J_rownnz;         // number of non-zeros in Jacobian row      (ntendon x 1)
    int*      ten_J_rowadr;         // row start address in colind array        (ntendon x 1)
    int*      ten_J_colind;         // column indices in sparse Jacobian        (ntendon x nv)
    mjtNum*   ten_length;           // tendon lengths                           (ntendon x 1)
    mjtNum*   ten_J;                // tendon Jacobian                          (ntendon x nv)
    int*      wrap_obj;             // geom id; -1: site; -2: pulley            (nwrap*2 x 1)
    mjtNum*   wrap_xpos;            // Cartesian 3D points in all path          (nwrap*2 x 3)

    // computed by mj_fwdPosition/mj_transmission
    mjtNum*   actuator_length;      // actuator lengths                         (nu x 1)
    mjtNum*   actuator_moment;      // actuator moments                         (nu x nv)

    // computed by mj_fwdPosition/mj_crb
    mjtNum*   crb;                  // com-based composite inertia and mass     (nbody x 10)

    //M*qacc + qfrc_bias = qfrc_applied + ctrl的M,惯性矩阵
	mjtNum*   qM;                   // total inertia                            (nM x 1)

    // computed by mj_fwdPosition/mj_factorM
    mjtNum*   qLD;                  // L'*D*L factorization of M                (nM x 1)
    mjtNum*   qLDiagInv;            // 1/diag(D)                                (nv x 1)
    mjtNum*   qLDiagSqrtInv;        // 1/sqrt(diag(D))                          (nv x 1)

    // computed by mj_fwdPosition/mj_collision
    mjContact* contact;             // list of all detected contacts            (nconmax x 1)

    // computed by mj_fwdPosition/mj_makeConstraint
    int*      efc_type;             // constraint type (mjtConstraint)          (njmax x 1)
    int*      efc_id;               // id of object of specified type           (njmax x 1)
    int*      efc_J_rownnz;         // number of non-zeros in Jacobian row      (njmax x 1)
    int*      efc_J_rowadr;         // row start address in colind array        (njmax x 1)
    int*      efc_J_rowsuper;       // number of subsequent rows in supernode   (njmax x 1)
    int*      efc_J_colind;         // column indices in Jacobian               (njmax x nv)
    int*      efc_JT_rownnz;        // number of non-zeros in Jacobian row    T (nv x 1)
    int*      efc_JT_rowadr;        // row start address in colind array      T (nv x 1)
    int*      efc_JT_rowsuper;      // number of subsequent rows in supernode T (nv x 1)
    int*      efc_JT_colind;        // column indices in Jacobian             T (nv x njmax)
    mjtNum*   efc_J;                // constraint Jacobian                      (njmax x nv)
    mjtNum*   efc_JT;               // constraint Jacobian transposed           (nv x njmax)
    mjtNum*   efc_pos;              // constraint position (equality, contact)  (njmax x 1)
    mjtNum*   efc_margin;           // inclusion margin (contact)               (njmax x 1)
    mjtNum*   efc_frictionloss;     // frictionloss (friction)                  (njmax x 1)
    mjtNum*   efc_diagApprox;       // approximation to diagonal of A           (njmax x 1)
    mjtNum*   efc_KBIP;             // stiffness, damping, impedance, imp'      (njmax x 4)
    mjtNum*   efc_D;                // constraint mass                          (njmax x 1)
    mjtNum*   efc_R;                // inverse constraint mass                  (njmax x 1)

    // computed by mj_fwdPosition/mj_projectConstraint
    int*      efc_AR_rownnz;        // number of non-zeros in AR                (njmax x 1)
    int*      efc_AR_rowadr;        // row start address in colind array        (njmax x 1)
    int*      efc_AR_colind;        // column indices in sparse AR              (njmax x njmax)
    mjtNum*   efc_AR;               // J*inv(M)*J' + R                          (njmax x njmax)

    //-------------------------------- POSITION, VELOCITY dependent

    // computed by mj_fwdVelocity
    mjtNum*   ten_velocity;         // tendon velocities                        (ntendon x 1)
    mjtNum*   actuator_velocity;    // actuator velocities                      (nu x 1)

    // computed by mj_fwdVelocity/mj_comVel
    mjtNum*   cvel;                 // com-based velocity [3D rot; 3D tran]     (nbody x 6)
    mjtNum*   cdof_dot;             // time-derivative of cdof                  (nv x 6)

	///M*qacc + qfrc_bias = qfrc_applied + ctrl中的qfrc_bias ,=C+G
    // computed by mj_fwdVelocity/mj_rne (without acceleration)
    mjtNum*   qfrc_bias;            // C(qpos,qvel)                             (nv x 1)

    // computed by mj_fwdVelocity/mj_passive
    mjtNum*   qfrc_passive;         // passive force                            (nv x 1)

    // computed by mj_fwdVelocity/mj_referenceConstraint
    mjtNum*   efc_vel;              // velocity in constraint space: J*qvel     (njmax x 1)
    mjtNum*   efc_aref;             // reference pseudo-acceleration            (njmax x 1)

    // computed by mj_sensorVel/mj_subtreeVel if needed
    mjtNum*   subtree_linvel;       // linear velocity of subtree com           (nbody x 3)
    mjtNum*   subtree_angmom;       // angular momentum about subtree com       (nbody x 3)

    //-------------------------------- POSITION, VELOCITY, CONTROL/ACCELERATION dependent

    // computed by mj_fwdActuation
    mjtNum*   actuator_force;       // actuator force in actuation space        (nu x 1)
    mjtNum*   qfrc_actuator;        // actuator force                           (nv x 1)

    // computed by mj_fwdAcceleration
    mjtNum*   qfrc_unc;             // net unconstrained force                  (nv x 1)
    mjtNum*   qacc_unc;             // unconstrained acceleration               (nv x 1)

    // computed by mj_fwdConstraint/mj_inverse
    mjtNum*   efc_b;                // linear cost term: J*qacc_unc - aref      (njmax x 1)
    mjtNum*   efc_force;            // constraint force in constraint space     (njmax x 1)
    int*      efc_state;            // constraint state (mjtConstraintState)    (njmax x 1)
    mjtNum*   qfrc_constraint;      // constraint force                         (nv x 1)

    // computed by mj_inverse
    mjtNum*   qfrc_inverse;         // net external force; should equal:        (nv x 1)
                                    //  qfrc_applied + J'*xfrc_applied + qfrc_actuator

    // computed by mj_sensorAcc/mj_rnePostConstraint if needed; rotation:translation format
    mjtNum*   cacc;                 // com-based acceleration                   (nbody x 6)
    mjtNum*   cfrc_int;             // com-based interaction force with parent  (nbody x 6)
    mjtNum*   cfrc_ext;             // com-based external force on body         (nbody x 6)
};
typedef struct _mjData mjData;

mj_fullM :复制惯性矩阵D到M
void mj_fullM(const mjModel* m, mjtNum* dst, const mjtNum* M);

Convert sparse inertia matrix M into full (i.e. dense) matrix.

mju_mulMatVec:矩阵和向量相乘接口
void mju_mulMatVec(mjtNum* res, const mjtNum* mat, const mjtNum* vec,
                   int nr, int nc);

Multiply matrix and vector: res = mat * vec.



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 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 nmesh;                      // number of meshes
  int nmeshvert;                  // number of vertices in all meshes
  int nmeshtexvert;               // number of vertices with 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 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

  // sizes set after mjModel construction (only affect mjData)
  int nM;                         // number of non-zeros in sparse inertia matrix
  int nemax;                      // number of potential equality-constraint rows
  int njmax;                      // number of available rows in constraint Jacobian
  int nconmax;                    // number of potential contacts in contact list
  int nstack;                     // number of fields in mjData stack
  int nuserdata;                  // number of extra fields in mjData
  int nsensordata;                // number of fields in sensor data vector

  int 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_geomnum;         // number of geoms                          (nbody x 1)
  int*      body_geomadr;         // start addr of geoms; -1: no geoms        (nbody x 1)
  mjtByte*  body_simple;          // body is simple (has diagonal M)          (nbody x 1)
  mjtByte*  body_sameframe;       // inertial frame is same as body frame     (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_user;            // user data                                (nbody x nuser_body)

  // 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)
  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_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_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                (ngeom x 1)
  int*      geom_group;           // group for visibility                     (ngeom x 1)
  int*      geom_priority;        // geom contact priority                    (ngeom x 1)
  mjtByte*  geom_sameframe;       // same as body frame (1) or iframe (2)     (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_rbound;          // radius of bounding sphere                (ngeom x 1)
  mjtNum*   geom_pos;             // local position offset rel. to body       (ngeom x 3)
  mjtNum*   geom_quat;            // local orientation offset rel. to body    (ngeom x 4)
  mjtNum*   geom_friction;        // friction for (slide, spin, roll)         (ngeom x 3)
  mjtNum*   geom_margin;          // detect contact if dist<margin            (ngeom x 1)
  mjtNum*   geom_gap;             // include in solver if dist<margin-gap     (ngeom x 1)
  mjtNum*   geom_user;            // user data                                (ngeom x nuser_geom)
  float*    geom_rgba;            // rgba when material is omitted            (ngeom x 4)

  // sites
  int*      site_type;            // geom type for rendering (mjtGeom)        (nsite x 1)
  int*      site_bodyid;          // id of site's body                        (nsite x 1)
  int*      site_matid;           // material id for rendering                (nsite x 1)
  int*      site_group;           // group for visibility                     (nsite x 1)
  mjtByte*  site_sameframe;       // same as body frame (1) or iframe (2)     (nsite x 1)
  mjtNum*   site_size;            // geom size for rendering                  (nsite x 3)
  mjtNum*   site_pos;             // local position offset rel. to body       (nsite x 3)
  mjtNum*   site_quat;            // local orientation offset rel. to body    (nsite x 4)
  mjtNum*   site_user;            // user data                                (nsite x nuser_site)
  float*    site_rgba;            // rgba when material is omitted            (nsite x 4)

  // cameras
  int*      cam_mode;             // camera tracking mode (mjtCamLight)       (ncam x 1)
  int*      cam_bodyid;           // id of camera's body                      (ncam x 1)
  int*      cam_targetbodyid;     // id of targeted body; -1: none            (ncam x 1)
  mjtNum*   cam_pos;              // position rel. to body frame              (ncam x 3)
  mjtNum*   cam_quat;             // orientation rel. to body frame           (ncam x 4)
  mjtNum*   cam_poscom0;          // global position rel. to sub-com in qpos0 (ncam x 3)
  mjtNum*   cam_pos0;             // global position rel. to body in qpos0    (ncam x 3)
  mjtNum*   cam_mat0;             // global orientation in qpos0              (ncam x 9)
  mjtNum*   cam_fovy;             // y-field of view (deg)                    (ncam x 1)
  mjtNum*   cam_ipd;              // inter-pupilary distance                  (ncam x 1)
  mjtNum*   cam_user;             // user data                                (ncam x nuser_cam)

  // lights
  int*      light_mode;           // light tracking mode (mjtCamLight)        (nlight x 1)
  int*      light_bodyid;         // id of light's body                       (nlight x 1)
  int*      light_targetbodyid;   // id of targeted body; -1: none            (nlight x 1)
  mjtByte*  light_directional;    // directional light                        (nlight x 1)
  mjtByte*  light_castshadow;     // does light cast shadows                  (nlight x 1)
  mjtByte*  light_active;         // is light on                              (nlight x 1)
  mjtNum*   light_pos;            // position rel. to body frame              (nlight x 3)
  mjtNum*   light_dir;            // direction rel. to body frame             (nlight x 3)
  mjtNum*   light_poscom0;        // global position rel. to sub-com in qpos0 (nlight x 3)
  mjtNum*   light_pos0;           // global position rel. to body in qpos0    (nlight x 3)
  mjtNum*   light_dir0;           // global direction in qpos0                (nlight x 3)
  float*    light_attenuation;    // OpenGL attenuation (quadratic model)     (nlight x 3)
  float*    light_cutoff;         // OpenGL cutoff                            (nlight x 1)
  float*    light_exponent;       // OpenGL exponent                          (nlight x 1)
  float*    light_ambient;        // ambient rgb (alpha=1)                    (nlight x 3)
  float*    light_diffuse;        // diffuse rgb (alpha=1)                    (nlight x 3)
  float*    light_specular;       // specular rgb (alpha=1)                   (nlight x 3)

  // meshes
  int*      mesh_vertadr;         // first vertex address                     (nmesh x 1)
  int*      mesh_vertnum;         // number of vertices                       (nmesh x 1)
  int*      mesh_texcoordadr;     // texcoord data address; -1: no texcoord   (nmesh x 1)
  int*      mesh_faceadr;         // first face address                       (nmesh x 1)
  int*      mesh_facenum;         // number of faces                          (nmesh x 1)
  int*      mesh_graphadr;        // graph data address; -1: no graph         (nmesh x 1)
  float*    mesh_vert;            // vertex positions for all meshe           (nmeshvert x 3)
  float*    mesh_normal;          // vertex normals for all meshes            (nmeshvert x 3)
  float*    mesh_texcoord;        // vertex texcoords for all meshes          (nmeshtexvert x 2)
  int*      mesh_face;            // triangle face data                       (nmeshface x 3)
  int*      mesh_graph;           // convex graph data                        (nmeshgraph x 1)

  // skins
  int*      skin_matid;           // skin material id; -1: none               (nskin x 1)
  float*    skin_rgba;            // skin rgba                                (nskin x 4)
  float*    skin_inflate;         // inflate skin in normal direction         (nskin x 1)
  int*      skin_vertadr;         // first vertex address                     (nskin x 1)
  int*      skin_vertnum;         // number of vertices                       (nskin x 1)
  int*      skin_texcoordadr;     // texcoord data address; -1: no texcoord   (nskin x 1)
  int*      skin_faceadr;         // first face address                       (nskin x 1)
  int*      skin_facenum;         // number of faces                          (nskin x 1)
  int*      skin_boneadr;         // first bone in skin                       (nskin x 1)
  int*      skin_bonenum;         // number of bones in skin                  (nskin x 1)
  float*    skin_vert;            // vertex positions for all skin meshes     (nskinvert x 3)
  float*    skin_texcoord;        // vertex texcoords for all skin meshes     (nskintexvert x 2)
  int*      skin_face;            // triangle faces for all skin meshes       (nskinface x 3)
  int*      skin_bonevertadr;     // first vertex in each bone                (nskinbone x 1)
  int*      skin_bonevertnum;     // number of vertices in each bone          (nskinbone x 1)
  float*    skin_bonebindpos;     // bind pos of each bone                    (nskinbone x 3)
  float*    skin_bonebindquat;    // bind quat of each bone                   (nskinbone x 4)
  int*      skin_bonebodyid;      // body id of each bone                     (nskinbone x 1)
  int*      skin_bonevertid;      // mesh ids of vertices in each bone        (nskinbonevert x 1)
  float*    skin_bonevertweight;  // weights of vertices in each bone         (nskinbonevert x 1)

  // height fields
  mjtNum*   hfield_size;          // (x, y, z_top, z_bottom)                  (nhfield x 4)
  int*      hfield_nrow;          // number of rows in grid                   (nhfield x 1)
  int*      hfield_ncol;          // number of columns in grid                (nhfield x 1)
  int*      hfield_adr;           // address in hfield_data                   (nhfield x 1)
  float*    hfield_data;          // elevation data                           (nhfielddata x 1)

  // textures
  int*      tex_type;             // texture type (mjtTexture)                (ntex x 1)
  int*      tex_height;           // number of rows in texture image          (ntex x 1)
  int*      tex_width;            // number of columns in texture image       (ntex x 1)
  int*      tex_adr;              // address in rgb                           (ntex x 1)
  mjtByte*  tex_rgb;              // rgb (alpha = 1)                          (ntexdata x 1)

  // materials
  int*      mat_texid;            // texture id; -1: none                     (nmat x 1)
  mjtByte*  mat_texuniform;       // make texture cube uniform                (nmat x 1)
  float*    mat_texrepeat;        // texture repetition for 2d mapping        (nmat x 2)
  float*    mat_emission;         // emission (x rgb)                         (nmat x 1)
  float*    mat_specular;         // specular (x white)                       (nmat x 1)
  float*    mat_shininess;        // shininess coef                           (nmat x 1)
  float*    mat_reflectance;      // reflectance (0: disable)                 (nmat x 1)
  float*    mat_rgba;             // rgba                                     (nmat x 4)

  // predefined geom pairs for collision detection; has precedence over exclude
  int*      pair_dim;             // contact dimensionality                   (npair x 1)
  int*      pair_geom1;           // id of geom1                              (npair x 1)
  int*      pair_geom2;           // id of geom2                              (npair x 1)
  int*      pair_signature;       // (body1+1)<<16 + body2+1                  (npair x 1)
  mjtNum*   pair_solref;          // constraint solver reference: contact     (npair x mjNREF)
  mjtNum*   pair_solimp;          // constraint solver impedance: contact     (npair x mjNIMP)
  mjtNum*   pair_margin;          // detect contact if dist<margin            (npair x 1)
  mjtNum*   pair_gap;             // include in solver if dist<margin-gap     (npair x 1)
  mjtNum*   pair_friction;        // tangent1, 2, spin, roll1, 2              (npair x 5)

  // excluded body pairs for collision detection
  int*      exclude_signature;    // (body1+1)<<16 + body2+1                  (nexclude x 1)

  // equality constraints
  int*      eq_type;              // constraint type (mjtEq)                  (neq x 1)
  int*      eq_obj1id;            // id of object 1                           (neq x 1)
  int*      eq_obj2id;            // id of object 2                           (neq x 1)
  mjtByte*  eq_active;            // enable/disable constraint                (neq x 1)
  mjtNum*   eq_solref;            // constraint solver reference              (neq x mjNREF)
  mjtNum*   eq_solimp;            // constraint solver impedance              (neq x mjNIMP)
  mjtNum*   eq_data;              // numeric data for constraint              (neq x mjNEQDATA)

  // tendons
  int*      tendon_adr;           // address of first object in tendon's path (ntendon x 1)
  int*      tendon_num;           // number of objects in tendon's path       (ntendon x 1)
  int*      tendon_matid;         // material id for rendering                (ntendon x 1)
  int*      tendon_group;         // group for visibility                     (ntendon x 1)
  mjtByte*  tendon_limited;       // does tendon have length limits           (ntendon x 1)
  mjtNum*   tendon_width;         // width for rendering                      (ntendon x 1)
  mjtNum*   tendon_solref_lim;    // constraint solver reference: limit       (ntendon x mjNREF)
  mjtNum*   tendon_solimp_lim;    // constraint solver impedance: limit       (ntendon x mjNIMP)
  mjtNum*   tendon_solref_fri;    // constraint solver reference: friction    (ntendon x mjNREF)
  mjtNum*   tendon_solimp_fri;    // constraint solver impedance: friction    (ntendon x mjNIMP)
  mjtNum*   tendon_range;         // tendon length limits                     (ntendon x 2)
  mjtNum*   tendon_margin;        // min distance for limit detection         (ntendon x 1)
  mjtNum*   tendon_stiffness;     // stiffness coefficient                    (ntendon x 1)
  mjtNum*   tendon_damping;       // damping coefficient                      (ntendon x 1)
  mjtNum*   tendon_frictionloss;  // loss due to friction                     (ntendon x 1)
  mjtNum*   tendon_lengthspring;  // tendon length in qpos_spring             (ntendon x 1)
  mjtNum*   tendon_length0;       // tendon length in qpos0                   (ntendon x 1)
  mjtNum*   tendon_invweight0;    // inv. weight in qpos0                     (ntendon x 1)
  mjtNum*   tendon_user;          // user data                                (ntendon x nuser_tendon)
  float*    tendon_rgba;          // rgba when material is omitted            (ntendon x 4)

  // list of all wrap objects in tendon paths
  int*      wrap_type;            // wrap object type (mjtWrap)               (nwrap x 1)
  int*      wrap_objid;           // object id: geom, site, joint             (nwrap x 1)
  mjtNum*   wrap_prm;             // divisor, joint coef, or site id          (nwrap x 1)

  // actuators
  int*      actuator_trntype;     // transmission type (mjtTrn)               (nu x 1)
  int*      actuator_dyntype;     // dynamics type (mjtDyn)                   (nu x 1)
  int*      actuator_gaintype;    // gain type (mjtGain)                      (nu x 1)
  int*      actuator_biastype;    // bias type (mjtBias)                      (nu x 1)
  int*      actuator_trnid;       // transmission id: joint, tendon, site     (nu x 2)
  int*      actuator_group;       // group for visibility                     (nu x 1)
  mjtByte*  actuator_ctrllimited; // is control limited                       (nu x 1)
  mjtByte*  actuator_forcelimited;// is force limited                         (nu x 1)
  mjtNum*   actuator_dynprm;      // dynamics parameters                      (nu x mjNDYN)
  mjtNum*   actuator_gainprm;     // gain parameters                          (nu x mjNGAIN)
  mjtNum*   actuator_biasprm;     // bias parameters                          (nu x mjNBIAS)
  mjtNum*   actuator_ctrlrange;   // range of controls                        (nu x 2)
  mjtNum*   actuator_forcerange;  // range of forces                          (nu x 2)
  mjtNum*   actuator_gear;        // scale length and transmitted force       (nu x 6)
  mjtNum*   actuator_cranklength; // crank length for slider-crank            (nu x 1)
  mjtNum*   actuator_acc0;        // acceleration from unit force in qpos0    (nu x 1)
  mjtNum*   actuator_length0;     // actuator length in qpos0                 (nu x 1)
  mjtNum*   actuator_lengthrange; // feasible actuator length range           (nu x 2)
  mjtNum*   actuator_user;        // user data                                (nu x nuser_actuator)

  // sensors
  int*      sensor_type;          // sensor type (mjtSensor)                  (nsensor x 1)
  int*      sensor_datatype;      // numeric data type (mjtDataType)          (nsensor x 1)
  int*      sensor_needstage;     // required compute stage (mjtStage)        (nsensor x 1)
  int*      sensor_objtype;       // type of sensorized object (mjtObj)       (nsensor x 1)
  int*      sensor_objid;         // id of sensorized object                  (nsensor x 1)
  int*      sensor_dim;           // number of scalar outputs                 (nsensor x 1)
  int*      sensor_adr;           // address in sensor array                  (nsensor x 1)
  mjtNum*   sensor_cutoff;        // cutoff for real and positive; 0: ignore  (nsensor x 1)
  mjtNum*   sensor_noise;         // noise standard deviation                 (nsensor x 1)
  mjtNum*   sensor_user;          // user data                                (nsensor x nuser_sensor)

  // custom numeric fields
  int*      numeric_adr;          // address of field in numeric_data         (nnumeric x 1)
  int*      numeric_size;         // size of numeric field                    (nnumeric x 1)
  mjtNum*   numeric_data;         // array of all numeric fields              (nnumericdata x 1)

  // custom text fields
  int*      text_adr;             // address of text in text_data             (ntext x 1)
  int*      text_size;            // size of text field (strlen+1)            (ntext x 1)
  char*     text_data;            // array of all text fields (0-terminated)  (ntextdata x 1)

  // custom tuple fields
  int*      tuple_adr;            // address of text in text_data             (ntuple x 1)
  int*      tuple_size;           // number of objects in tuple               (ntuple x 1)
  int*      tuple_objtype;        // array of object types in all tuples      (ntupledata x 1)
  int*      tuple_objid;          // array of object ids in all tuples        (ntupledata x 1)
  mjtNum*   tuple_objprm;         // array of object params in all tuples     (ntupledata x 1)

  // keyframes
  mjtNum*   key_time;             // key time                                 (nkey x 1)
  mjtNum*   key_qpos;             // key position                             (nkey x nq)
  mjtNum*   key_qvel;             // key velocity                             (nkey x nv)
  mjtNum*   key_act;              // key activation                           (nkey x na)
  mjtNum*   key_mpos;             // key mocap position                       (nkey x 3*nmocap)
  mjtNum*   key_mquat;            // key mocap quaternion                     (nkey x 4*nmocap)

  // names
  int*      name_bodyadr;         // body name pointers                       (nbody x 1)
  int*      name_jntadr;          // joint name pointers                      (njnt x 1)
  int*      name_geomadr;         // geom name pointers                       (ngeom x 1)
  int*      name_siteadr;         // site name pointers                       (nsite x 1)
  int*      name_camadr;          // camera name pointers                     (ncam x 1)
  int*      name_lightadr;        // light name pointers                      (nlight x 1)
  int*      name_meshadr;         // mesh name pointers                       (nmesh x 1)
  int*      name_skinadr;         // skin name pointers                       (nskin x 1)
  int*      name_hfieldadr;       // hfield name pointers                     (nhfield x 1)
  int*      name_texadr;          // texture name pointers                    (ntex x 1)
  int*      name_matadr;          // material name pointers                   (nmat x 1)
  int*      name_pairadr;         // geom pair name pointers                  (npair x 1)
  int*      name_excludeadr;      // exclude name pointers                    (nexclude x 1)
  int*      name_eqadr;           // equality constraint name pointers        (neq x 1)
  int*      name_tendonadr;       // tendon name pointers                     (ntendon x 1)
  int*      name_actuatoradr;     // actuator name pointers                   (nu x 1)
  int*      name_sensoradr;       // sensor name pointers                     (nsensor x 1)
  int*      name_numericadr;      // numeric name pointers                    (nnumeric x 1)
  int*      name_textadr;         // text name pointers                       (ntext x 1)
  int*      name_tupleadr;        // tuple name pointers                      (ntuple x 1)
  int*      name_keyadr;          // keyframe name pointers                   (nkey x 1)
  char*     names;                // names of all objects, 0-terminated       (nnames x 1)
};
typedef struct mjModel_ mjModel;
  • 1
    点赞
  • 3
    收藏
    觉得还不错? 一键收藏
  • 0
    评论
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值