模型描述的高级数据结构 mjCModel
我们在初识仿真系统模型时提到,MuJoCo 通过 mj_loadXML 把上层的描述文件加载到内存时, 会通过解析器(parser)将其转换为上层的 C++ 数据结构 mjCModel。它只是一个中间结构,实际仿真中,还会将之转换成底层的 C 结构 mjModel。之后,mjCModel 对象就没有用了,可以丢了。 毕竟高级的数据结构是设计给人类看的,我们可以直接通过它来描述仿真场景。
本文,我们从 MJCF 文件解析器的代码入手,详细解析 mjCModel 的构成和构造方法。
1. MJCF 标签概述
前文已经介绍了 MJCF 是如何通过 body 标签描述仿真系统中各个物体的拓扑关系, 在标签 default 中设定默认参数。除此之外,MuJoCo 还需要很多配置项来完整描述一个仿真系统,为此,MJCF 还定义了很多标签。 为了标识一个 xml 文件是 MJCF 格式的,其中有且仅有一个 mujoco 标签,并且该标签必须在最上层。下面我们概述可以直接写在 mujoco 下的子标签, 详细说明可以参见官方文档。
我们在分析函数 mjParseXML 的时候看到, MuJoCo 通过类 mjXReader 完成 MJCF 文件的解析工作。 类 mjXReader 将可以直接写在 mujoco 下的子标签称为 section, 如下面的代码片段所示,mjXReader 为每个 section 提供了一个解析函数。
// XML sections embedded in all formats
static void Compiler(tinyxml2::XMLElement* section, mjCModel* mod); // compiler section
static void Option(tinyxml2::XMLElement* section, mjOption* opt); // option section
static void Size(tinyxml2::XMLElement* section, mjCModel* mod); // size section
// XML section specific to MJCF
void Default(tinyxml2::XMLElement* section, int parentid); // default section
void Extension(tinyxml2::XMLElement* section); // extension section
void Custom(tinyxml2::XMLElement* section); // custom section
void Visual(tinyxml2::XMLElement* section); // visual section
void Statistic(tinyxml2::XMLElement* section); // statistic section
void Asset(tinyxml2::XMLElement* section); // asset section
void Body(tinyxml2::XMLElement* section, mjCBody* pbody, mjCFrame* pframe); // body/world section
void Contact(tinyxml2::XMLElement* section); // contact section
void Deformable(tinyxml2::XMLElement* section); // deformable section
void Equality(tinyxml2::XMLElement* section); // equality section
void Tendon(tinyxml2::XMLElement* section); // tendon section
void Actuator(tinyxml2::XMLElement* section); // actuator section
void Sensor(tinyxml2::XMLElement* section); // sensor section
void Keyframe(tinyxml2::XMLElement* section); // keyframe section
! | required element, can appear only once |
---|---|
? | optional element, can appear only once |
* | optional element, can appear many times |
R | optional element, can appear many times recursively |
- compiler (*): 该标签用于设置内置解析器和编译器的选项。解析和编译后不再有任何作用。这里的设置是全局的,适用于整个模型。
- option (*): 该标签与
mjModel
的字段mjModel.opt
中包含的低级结构mjOption
一一对应。 用于设定一些仿真参数,比如时间步长 timestep 等。该标签不会以任何方式影响编译过程,只是被简单的复制到低级模型中。 - size (*): 该标签用于设定那些无法通过模型中的元素推断出的参数,比如指定动态分配内存大小的 memory 等。该标签描述的属性在运行时是不能修改的。
- default (R): 该标签已经在前文中详细分析过了, 用于描述仿真要素的默认配置。
- visual (*): 该标签与
mjModel
的字段mjModel.vis
中包含的低级结构mjVisual
一一对应,用于修改可视化工具的通用配置。 - statistic (*): 该标签用于覆盖编译器计算的模型统计信息,比如平均质量 meanmass。这些统计数据不仅提供信息,而且还用于缩放渲染和扰动。
- asset (*): 该标签没有属性,主要用于标记资源(比如 mesh、纹理、材质等),方便在模型中引用它。
- (world)body (R): 该标签已经在前文中详细分析过了, 用于通过 xml 的嵌套关系描述仿真系统的运动树。
- contact (*): 该标签没有属性,用于设置仿真要素之间的碰撞关系的。
- deformable (*): 该标签没有属性,用于对可变形对象的进行分组。
- equality (*): 该标签没有属性,用于描述等式约束,可以用于描述闭环系统。
- tendon (*): 该标签用于定义肌腱。肌腱可以用于施加长度约束,模拟弹簧、阻尼和摩擦力。我们可以为之附着执行器。
- actuator (*): 该标签用于定义执行器。
- sensor (*): 该标签用于定义传感器。
- keyframe (*): 该标签用于定义关键帧。可以用于创建一些特殊的状态库,并将仿真状态初始化为其中之一。
- custom (*): 该标签用于自定义一些数组和文本。
- extension (*): 该标签是 Mujoco 的扩展接口,允许用户以插件的形式植入自定义的代码逻辑。
下面是函数 mjXReader::Parse()
的代码片段。
该函数负责解析 xml 文件,大体上分为语法检查和模型构造两个阶段。如下面的片段所示,在函数的一开始,mjXReader 通过 mjXSchema 类型的成员变量 schema 检查文件是否存在语法错误。
void mjXReader::Parse(XMLElement* root) {
if (!schema.GetError().empty())
throw mjXError(0, "XML Schema Construction Error: %s\n", schema.GetError().c_str());
XMLElement* bad = 0;
if ((bad = schema.Check(root, 0)))
throw mjXError(bad, "Schema violation: %s\n", schema.GetError().c_str());
然后从 xml 的根节点上获取模型的名称,如果紧跟着 mujoco 的开始标签是一个注释项(如右图所示),还会将其专门保存到 model->comment
中。
ReadAttrTxt(root, "model", model->modelname);
if (root->FirstChild() && root->FirstChild()->ToComment()) {
model->comment = root->FirstChild()->Value();
} else {
model->comment.clear();
}
接下来,就是逐项解析各个 section。通过 FirstChildElement 获取指定类型的 section 标签,然后通过 NextSiblingElement 实现迭代器, 并在 for 循环内部通过各 section 的解析函数完成模型的构造。
// 套路都一样,这里只保留了 compiler 作为示例
for (XMLElement* section = root->FirstChildElement("compiler"); section; section = section->NextSiblingElement("compiler"))
Compiler(section, model);
}
2. 类 mjCModel 的关键成员
MuJoCo 的模块 src/user 中实现了面向用户的上层接口。
类 mjCModel 就被定义在 src/user/user_model.h 中,
它与MJCF 格式中定义各个标签和属性是一一对应的,包含生成低级模型所需的一切信息。
我们可以通过调用"Add"前缀的函数、设置各个对象的公共字段来手动构造之。但更推荐通过加载 xml 描述文件来获得一个高级对象。
完成 mjCModel 对象的构建之后,就可以调用 Compile
来生成相应的低级模型对象。至此 mjCModel 对象的使命就结束了。
在下面的代码片段中,除了构造和析构函数之外,还声明了四个函数。其中 Compile 用于生成低级模型对象,CopyBack 则是 Compile 的反函数用于从低级模型反编译回高级模型。 FuseStatic 用于合并那些静态连接的刚体。如果在一个 body 的标签中没有定义 joint,那么该刚体将被认为与父节点固连在一起,FuseStatic 可以将他们整体看做是一个刚体。 一旦有刚体被合并了,就需要调用 FuseReindex 对刚体和关节重新编号。
class mjCModel {
// 省略友元的声明
public:
mjCModel(); // constructor
~mjCModel(); // destructor
mjModel* Compile(const mjVFS* vfs = 0); // COMPILER: construct mjModel
bool CopyBack(const mjModel*); // DECOMPILER: copy numeric back
void FuseStatic(void); // fuse static bodies with parent
void FuseReindex(mjCBody* body); // reindex elements during fuse
下面的代码片段中声明了各种 Add 前缀的成员函数。通过这些接口 mjCModel 会帮我们构建一个指定类型的模型元素对象,比如纹理(texture)、执行器(actuator)等。 我们还需要拿着这些元素对象填充上合适的属性值。这些元素对象都派生自 mjCBase。
mjCFlex* AddFlex(void); // flex
mjCMesh* AddMesh(mjCDef* def = 0); // mesh
mjCSkin* AddSkin(void); // skin
mjCHField* AddHField(void); // heightfield
mjCTexture* AddTexture(void); // texture
mjCMaterial* AddMaterial(mjCDef* def = 0); // material
mjCPair* AddPair(mjCDef* def = 0); // geom pair for inclusion
mjCBodyPair* AddExclude(void); // body pair for exclusion
mjCEquality* AddEquality(mjCDef* def = 0); // equality constraint
mjCTendon* AddTendon(mjCDef* def = 0); // tendon
mjCActuator* AddActuator(mjCDef* def = 0); // actuator
mjCSensor* AddSensor(void); // sensor
mjCNumeric* AddNumeric(void); // custom numeric
mjCText* AddText(void); // custom text
mjCTuple* AddTuple(void); // custom tuple
mjCKey* AddKey(void); // keyframe
mjCPlugin* AddPlugin(void); // plugin instance
通过如下的接口,我们可以指定删除某些个元素、获取特定类型的元素数量、访问某个特定类型的元素。
// delete elements marked as discard=true
template <class T>
void Delete(std::vector<T*>& elements, const std::vector<bool>& discard);
template <class T>
void DeleteAll(std::vector<T*>& elements); // delete all elements
int NumObjects(mjtObj type); // number of objects in specified list
mjCBase* GetObject(mjtObj type, int id); // pointer to specified object
成员变量 comment 就是在解析函数中提到的关于模型的描述。modelfiledir 则是模型文件的路径, defaults 中记录了模型文件中定义的所有默认参数配置。
std::string comment; // comment at top of XML
std::string modelfiledir; // path to model file
std::vector<mjCDef*> defaults; // settings for each defaults class
下面是关于 compiler, statistic, size 的配置,以及装载各类元素的容器。它们基本上与 xml 的描述完全对应的。
bool autolimits; // infer "limited" attribute based on range
double boundmass; // enforce minimum body mass
double boundinertia; // enforce minimum body diagonal inertia
double settotalmass; // rescale masses and inertias; <=0: ignore
bool balanceinertia; // automatically impose A + B >= C rule
bool strippath; // automatically strip paths from mesh files
bool fitaabb; // meshfit to aabb instead of inertia box
bool degree; // angles in radians or degrees
char euler[3]; // sequence for euler rotations
std::string meshdir; // mesh and hfield directory
std::string texturedir; // texture directory
bool discardvisual; // discard visual geoms in parser
bool convexhull; // compute mesh convex hulls
bool usethread; // use multiple threads to speed up compiler
bool fusestatic; // fuse static bodies with parent
int inertiafromgeom; // use geom inertias (mjtInertiaFromGeom)
int inertiagrouprange[2]; // range of geom groups used to compute inertia
bool exactmeshinertia; // if false, use old formula
mjLROpt LRopt; // options for lengthrange computation
double meaninertia; // mean diagonal inertia
double meanmass; // mean body mass
double meansize; // mean body size
double extent; // spatial extent
double center[3]; // center of model
std::string modelname; // model name
mjOption option; // options
mjVisual visual; // visual options
std::size_t memory; // size of arena+stack memory in bytes
int nemax; // max number of equality constraints
int njmax; // max number of constraints (Jacobian rows)
int nconmax; // max number of detected contacts (mjContact array size)
size_t nstack; // (deprecated) number of fields in mjData stack
int nuserdata; // number extra fields in mjData
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
std::vector<mjCFlex*> flexes; // list of flexes
std::vector<mjCMesh*> meshes; // list of meshes
std::vector<mjCSkin*> skins; // list of skins
std::vector<mjCHField*> hfields; // list of height fields
std::vector<mjCTexture*> textures; // list of textures
std::vector<mjCMaterial*> materials; // list of materials
std::vector<mjCPair*> pairs; // list of geom pairs to include
std::vector<mjCBodyPair*> excludes; // list of body pairs to exclude
std::vector<mjCEquality*> equalities; // list of equality constraints
std::vector<mjCTendon*> tendons; // list of tendons
std::vector<mjCActuator*> actuators; // list of actuators
std::vector<mjCSensor*> sensors; // list of sensors
std::vector<mjCNumeric*> numerics; // list of numeric fields
std::vector<mjCText*> texts; // list of text fields
std::vector<mjCTuple*> tuples; // list of tuple fields
std::vector<mjCKey*> keys; // list of keyframe fields
std::vector<std::pair<const mjpPlugin*, int>> active_plugins; // list of active plugins
std::vector<mjCPlugin*> plugins; // list of plugin instances
// pointers to objects created inside kinematic tree
std::vector<mjCBody*> bodies; // list of bodies
std::vector<mjCJoint*> joints; // list of joints allowing motion relative to parent
std::vector<mjCGeom*> geoms; // list of geoms attached to this body
std::vector<mjCSite*> sites; // list of sites attached to this body
std::vector<mjCCamera*> cameras; // list of cameras
std::vector<mjCLight*> lights; // list of lights
此外,还有一些成员变量记录了模型中各类对象的数量,以及编译过程中的生成的一些信息,它们将被传递给编译后的底层模型对象中。
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 nflex; // number of flexes
int nmesh; // number of meshes
int nskin; // number of skins
int nhfield; // number of height fields
int ntex; // number of textures
int nmat; // number of materials
int npair; // number of geom pairs in pair array
int nexclude; // number of excluded body pairs
int neq; // number of equality constraints
int ntendon; // number of tendons
int nsensor; // number of sensors
int nnumeric; // number of numeric fields
int ntext; // number of text fields
int ntuple; // number of tuple fields
int nkey; // number of keyframes
int nmocap; // number of mocap bodies
int nplugin; // number of plugin instances
int nq; // number of generalized coordinates = dim(qpos)
int nv; // number of degrees of freedom = dim(qvel)
int nu; // number of actuators/controls
int na; // number of activation variables
int nbvh; // number of total boundary volume hierarchies
int nbvhstatic; // number of static boundary volume hierarchies
int nbvhdynamic; // number of dynamic boundary volume hierarchies
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 nflexshelldata; // number of shell fragment vertex ids in all flexes
int nflexevpair; // number of element-vertex pairs in all flexes
int nflextexcoord; // number of vertex texture coordinates in all flexes
int nmeshvert; // number of vertices in all meshes
int nmeshnormal; // number of normals in all meshes
int nmeshtexcoord; // number of texture coordinates in all meshes
int nmeshface; // number of triangular faces in all meshes
int nmeshgraph; // number of shorts in mesh auxiliary data
int nskinvert; // number of vertices in all skins
int nskintexvert; // number of vertices with texcoord in all skins
int nskinface; // number of faces in all skins
int nskinbone; // number of bones in all skins
int nskinbonevert; // number of vertices in all skins
int nhfielddata; // number of data points in all hfields
int ntexdata; // number of texture bytes
int nwrap; // number of wrap objects in all tendon paths
int nsensordata; // number of mjtNums in sensor data vector
int nnumericdata; // number of mjtNums in all custom fields
int ntextdata; // number of chars in all text fields, including 0
int ntupledata; // number of objects in all tuple fields
int npluginattr; // number of chars in all plugin config attributes
int nnames; // number of chars in all names
int npaths; // number of chars in all paths
int nM; // number of non-zeros in sparse inertia matrix
int nD; // number of non-zeros in sparse dof-dof matrix
int nB; // number of non-zeros in sparse body-dof matrix