MuJoCo 学习笔记:仿真数据类型 mjData

在 MuJoCo 中,mjData 用于存放仿真数据,即给定模型后,当前的状态数据。比如,各个对象的位置、各关节的角度、碰撞信息等等。下面,详细解析 mjData 中各个变量的含义。


1. mjContact

mjContact 是表示碰撞结果的类,其定义如下:

struct mjContact_ {                // result of collision detection functions
  // contact parameters set by near-phase collision function
  mjtNum  dist;                    // distance between nearest points; neg: penetration
  mjtNum  pos[3];                  // position of contact point: midpoint between geoms
  mjtNum  frame[9];                // normal is in [0-2], points from geom[0] to geom[1]

  // contact parameters set by mj_collideGeoms
  mjtNum  includemargin;           // include if dist<includemargin=margin-gap
  mjtNum  friction[5];             // tangent1, 2, spin, roll1, 2
  mjtNum  solref[mjNREF];          // constraint solver reference, normal direction
  mjtNum  solreffriction[mjNREF];  // constraint solver reference, friction directions
  mjtNum  solimp[mjNIMP];          // constraint solver impedance

  // internal storage used by solver
  mjtNum  mu;                      // friction of regularized cone, set by mj_makeConstraint
  mjtNum  H[36];                   // cone Hessian, set by mj_constraintUpdate

  // contact descriptors set by mj_collideXXX
  int     dim;                     // contact space dimensionality: 1, 3, 4 or 6
  int     geom1;                   // id of geom 1; deprecated, use geom[0]
  int     geom2;                   // id of geom 2; deprecated, use geom[1]
  int     geom[2];                 // geom ids; -1 for flex
  int     flex[2];                 // flex ids; -1 for geom
  int     elem[2];                 // element ids; -1 for geom or flex vertex
  int     vert[2];                 // vertex ids;  -1 for geom or flex element

  // flag set by mj_setContact or mj_instantiateContact
  int     exclude;                 // 0: include, 1: in gap, 2: fused, 3: no dofs

  // address computed by mj_instantiateContact
  int     efc_address;             // address in efc; -1: not included
};
typedef struct mjContact_ mjContact;

其中,dist 是碰撞深度/距离,即 A、B 两物体之间最近的距离;pos[3] 是碰撞点,是 A、B 两物体相交处的中点;frame[9] 则依次存放了法向量,A 上的碰撞点,B 上的碰撞点。这部分信息的示意图如下:
(待补充)

includemargin 是 *** 某边界信息 *** ;friction[5] 是摩擦信息,包括了 tangent,spin,roll,具体入下示意图:
(待补充)

solref[mjNREF] 是 **** ;solreffriction[mjNREF] 是 **** ;solimp[mjNIMP] 是 *** ;

mu 是 *** ;H[36] 是 **** 。具体理论推导如下:
(待补充)

dim 是碰撞空间维度(1,3, 4,or 6),具体含义是***;

geom1 是物体 A 的编号;geom2 是物体 B 的编号。(注:这两个变量已 deprecated,推荐使用 geom[2])。

geom[2] 里面存放了物体 A 和 B 的编号,如果值是 -1,则意味着该物体时 flex;flex[2] 里存放了物体 A 和 B 的编号,如果值是 -1,则意味着该物体是 geom;elem[2] 里存放了单元的编号,如果值是 -1,则意味着是顶点;vert[2] 里存放了顶点的编号,如果值是 -1,则意味着是单元。举个例子, ***。

exclude 表示 ***;

efc_address 表示 ***;


2. mjSolverStat

mjSolverStat 是表示求解器状态的类,其定义如下:

struct mjSolverStat_ {       // per-iteration solver statistics
  mjtNum  improvement;       // cost reduction, scaled by 1/trace(M(qpos0))
  mjtNum  gradient;          // gradient norm (primal only, scaled)
  mjtNum  lineslope;         // slope in linesearch
  int     nactive;           // number of active constraints
  int     nchange;           // number of constraint state changes
  int     neval;             // number of cost evaluations in line search
  int     nupdate;           // number of Cholesky updates in line search
};
typedef struct mjSolverStat_ mjSolverStat;

其中,improvement 表示 *** ;gradient 表示 *** ;lineslope 表示 *** ;

nactivate 表示当前激活的约束数量;nchange 表示当前状态发生变化的约束的数量,(注:状态发生变化指的是 *** );neval 表示 *** ;nupdate 表示 *** ;


3. mjData

mjData 是表示仿真数据的类,其中,比较基础的数据有输入/输出相关的、位置相关、位置-速度相关、位置-速度-控制/加速度相关、arena-allocated 等。下面分别介绍:

3.1 main inputs and outputs of the computation

这部分数据如下定义:

  //-------------------- 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)
  mjtNum* plugin_state;      // plugin state                                     (npluginstate x 1)

  // control
  mjtNum* ctrl;              // control                                          (nu x 1)
  mjtNum* qfrc_applied;      // applied generalized force                        (nv x 1)
  mjtNum* xfrc_applied;      // applied Cartesian force/torque                   (nbody x 6)
  mjtByte* eq_active;        // enable/disable constraints                       (neq x 1)

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

  // dynamics
  mjtNum* qacc;              // acceleration                                     (nv x 1)
  mjtNum* act_dot;           // time-derivative of actuator activation           (na x 1)

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

  // sensors
  mjtNum* sensordata;        // sensor data array                                (nsensordata x 1)

  // plugins
  int*       plugin;         // copy of m->plugin, required for deletion         (nplugin x 1)
  uintptr_t* plugin_data;    // pointer to plugin-managed data structure         (nplugin x 1)

其中,qpos 是所有物体的位置数据;qvel 是所有对象的速度数据;act 是所有驱动器(actuator activation)的激活数据;qacc_warmstart 是 *** ;plugin_state 是插件的状态。注:插件的状态指的是 *** 。

ctrl 是控制相关的数据,用于 *** ;qfrc_applied 是施加在物体上的力, *** 坐标系下,例如 *** ;xfrc_applied 是施加在物体上的力/力矩,Cartesian 坐标系下;eq_activate 是所有 equal constriant 的开启/禁用标志位,这里设置标志位的作用是 *** 。

mocap_pos 是 mocap 对象的位置,即 *** ;mocap_quat 是 mocap 对象的位姿;(注:mocap 指的是 *** )

qacc 是物体的加速度;act_dot 是驱动器激活数据对时间的导数(类似于加速度),这项数据主要用于 *** 。

userdata 用户数据,一般可以用来 *** 。

sensordata 传感器数据,例如 *** ,一般是用来 *** 。

plugin 插件的指针,貌似是为了释放内存的;plugin_data 指向插件管理的数据地址;

3.2 POSITION dependent

位置相关的数据,其定义如下:

  //-------------------- 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 (rot:lin)      (nv x 6)
  mjtNum* cinert;            // com-based body inertia and mass                  (nbody x 10)

  // computed by mj_fwdPosition/mj_flex
  mjtNum* flexvert_xpos;     // Cartesian flex vertex positions                  (nflexvert x 3)
  mjtNum* flexelem_aabb;     // flex element bounding boxes (center, size)       (nflexelem x 6)
  int*    flexedge_J_rownnz; // number of non-zeros in Jacobian row              (nflexedge x 1)
  int*    flexedge_J_rowadr; // row start address in colind array                (nflexedge x 1)
  int*    flexedge_J_colind; // column indices in sparse Jacobian                (nflexedge x nv)
  mjtNum* flexedge_J;        // flex edge Jacobian                               (nflexedge x nv)
  mjtNum* flexedge_length;   // flex edge lengths                                (nflexedge x 1)

  // 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_J;             // tendon Jacobian                                  (ntendon x nv)
  mjtNum* ten_length;        // tendon lengths                                   (ntendon x 1)
  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)
  mjtNum* qM;                // total inertia (sparse)                           (nM x 1)

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

  // computed by mj_collisionTree
  mjtNum*  bvh_aabb_dyn;     // global bounding box (center, size)               (nbvhdynamic x 6)
  mjtByte* bvh_active;       // was bounding volume checked for collision        (nbvh x 1)
posted @ 2024-08-29 18:17  wghou09  阅读(105)  评论(0编辑  收藏  举报