diff --git a/doc/includes/references.h b/doc/includes/references.h index 15345e994c..6cbecfd432 100644 --- a/doc/includes/references.h +++ b/doc/includes/references.h @@ -1743,7 +1743,6 @@ typedef struct mjsFrame_ { // frame specification typedef struct mjsJoint_ { // joint specification mjsElement* element; // element type mjString* name; // name - mjString* classname; // class name mjtJoint type; // joint type // kinematics @@ -1781,7 +1780,6 @@ typedef struct mjsJoint_ { // joint specification typedef struct mjsGeom_ { // geom specification mjsElement* element; // element type mjString* name; // name - mjString* classname; // classname mjtGeom type; // geom type // frame, size @@ -1828,7 +1826,6 @@ typedef struct mjsGeom_ { // geom specification typedef struct mjsSite_ { // site specification mjsElement* element; // element type mjString* name; // name - mjString* classname; // class name // frame, size double pos[3]; // position @@ -1850,7 +1847,6 @@ typedef struct mjsSite_ { // site specification typedef struct mjsCamera_ { // camera specification mjsElement* element; // element type mjString* name; // name - mjString* classname; // class name // extrinsics double pos[3]; // position @@ -1878,7 +1874,6 @@ typedef struct mjsCamera_ { // camera specification typedef struct mjsLight_ { // light specification mjsElement* element; // element type mjString* name; // name - mjString* classname; // class name // frame double pos[3]; // position @@ -1904,7 +1899,6 @@ typedef struct mjsLight_ { // light specification typedef struct mjsFlex_ { // flex specification mjsElement* element; // element type mjString* name; // name - mjString* classname; // class name // contact properties int contype; // contact type @@ -1943,7 +1937,6 @@ typedef struct mjsFlex_ { // flex specification typedef struct mjsMesh_ { // mesh specification mjsElement* element; // element type mjString* name; // name - mjString* classname; // class name mjString* content_type; // content type of file mjString* file; // mesh file double refpos[3]; // reference position @@ -1974,7 +1967,6 @@ typedef struct mjsHField_ { // height field specification typedef struct mjsSkin_ { // skin specification mjsElement* element; // element type mjString* name; // name - mjString* classname; // class name mjString* file; // skin file mjString* material; // name of material used for rendering float rgba[4]; // rgba when material is omitted @@ -1999,7 +1991,6 @@ typedef struct mjsSkin_ { // skin specification typedef struct mjsTexture_ { // texture specification mjsElement* element; // element type mjString* name; // name - mjString* classname; // class name mjtTexture type; // texture type // method 1: builtin @@ -2031,7 +2022,6 @@ typedef struct mjsTexture_ { // texture specification typedef struct mjsMaterial_ { // material specification mjsElement* element; // element type mjString* name; // name - mjString* classname; // class name mjString* texture; // name of texture (empty: none) mjtByte texuniform; // make texture cube uniform float texrepeat[2]; // texture repetition for 2D mapping @@ -2047,7 +2037,6 @@ typedef struct mjsMaterial_ { // material specification typedef struct mjsPair_ { // pair specification mjsElement* element; // element type mjString* name; // name - mjString* classname; // class name mjString* geomname1; // name of geom 1 mjString* geomname2; // name of geom 2 @@ -2071,7 +2060,6 @@ typedef struct mjsExclude_ { // exclude specification typedef struct mjsEquality_ { // equality specification mjsElement* element; // element type mjString* name; // name - mjString* classname; // class name mjtEq type; // constraint type double data[mjNEQDATA]; // type-dependent data mjtByte active; // is equality initially active @@ -2084,7 +2072,6 @@ typedef struct mjsEquality_ { // equality specification typedef struct mjsTendon_ { // tendon specification mjsElement* element; // element type mjString* name; // name - mjString* classname; // class name // stiffness, damping, friction double stiffness; // stiffness coefficient @@ -2118,7 +2105,6 @@ typedef struct mjsWrap_ { // wrapping object specification typedef struct mjsActuator_ { // actuator specification mjsElement* element; // element type mjString* name; // name - mjString* classname; // class name // gain, bias mjtGain gaintype; // gain type @@ -2160,7 +2146,6 @@ typedef struct mjsActuator_ { // actuator specification typedef struct mjsSensor_ { // sensor specification mjsElement* element; // element type mjString* name; // name - mjString* classname; // class name // sensor definition mjtSensor type; // type of sensor diff --git a/include/mujoco/mjspec.h b/include/mujoco/mjspec.h index 91f284c7c6..d9ed53fa20 100644 --- a/include/mujoco/mjspec.h +++ b/include/mujoco/mjspec.h @@ -222,7 +222,6 @@ typedef struct mjsFrame_ { // frame specification typedef struct mjsJoint_ { // joint specification mjsElement* element; // element type mjString* name; // name - mjString* classname; // class name mjtJoint type; // joint type // kinematics @@ -262,7 +261,6 @@ typedef struct mjsJoint_ { // joint specification typedef struct mjsGeom_ { // geom specification mjsElement* element; // element type mjString* name; // name - mjString* classname; // classname mjtGeom type; // geom type // frame, size @@ -311,7 +309,6 @@ typedef struct mjsGeom_ { // geom specification typedef struct mjsSite_ { // site specification mjsElement* element; // element type mjString* name; // name - mjString* classname; // class name // frame, size double pos[3]; // position @@ -335,7 +332,6 @@ typedef struct mjsSite_ { // site specification typedef struct mjsCamera_ { // camera specification mjsElement* element; // element type mjString* name; // name - mjString* classname; // class name // extrinsics double pos[3]; // position @@ -365,7 +361,6 @@ typedef struct mjsCamera_ { // camera specification typedef struct mjsLight_ { // light specification mjsElement* element; // element type mjString* name; // name - mjString* classname; // class name // frame double pos[3]; // position @@ -393,7 +388,6 @@ typedef struct mjsLight_ { // light specification typedef struct mjsFlex_ { // flex specification mjsElement* element; // element type mjString* name; // name - mjString* classname; // class name // contact properties int contype; // contact type @@ -434,7 +428,6 @@ typedef struct mjsFlex_ { // flex specification typedef struct mjsMesh_ { // mesh specification mjsElement* element; // element type mjString* name; // name - mjString* classname; // class name mjString* content_type; // content type of file mjString* file; // mesh file double refpos[3]; // reference position @@ -470,7 +463,6 @@ typedef struct mjsHField_ { // height field specification typedef struct mjsSkin_ { // skin specification mjsElement* element; // element type mjString* name; // name - mjString* classname; // class name mjString* file; // skin file mjString* material; // name of material used for rendering float rgba[4]; // rgba when material is omitted @@ -497,7 +489,6 @@ typedef struct mjsSkin_ { // skin specification typedef struct mjsTexture_ { // texture specification mjsElement* element; // element type mjString* name; // name - mjString* classname; // class name mjtTexture type; // texture type // method 1: builtin @@ -531,7 +522,6 @@ typedef struct mjsTexture_ { // texture specification typedef struct mjsMaterial_ { // material specification mjsElement* element; // element type mjString* name; // name - mjString* classname; // class name mjString* texture; // name of texture (empty: none) mjtByte texuniform; // make texture cube uniform float texrepeat[2]; // texture repetition for 2D mapping @@ -549,7 +539,6 @@ typedef struct mjsMaterial_ { // material specification typedef struct mjsPair_ { // pair specification mjsElement* element; // element type mjString* name; // name - mjString* classname; // class name mjString* geomname1; // name of geom 1 mjString* geomname2; // name of geom 2 @@ -577,7 +566,6 @@ typedef struct mjsExclude_ { // exclude specification typedef struct mjsEquality_ { // equality specification mjsElement* element; // element type mjString* name; // name - mjString* classname; // class name mjtEq type; // constraint type double data[mjNEQDATA]; // type-dependent data mjtByte active; // is equality initially active @@ -592,7 +580,6 @@ typedef struct mjsEquality_ { // equality specification typedef struct mjsTendon_ { // tendon specification mjsElement* element; // element type mjString* name; // name - mjString* classname; // class name // stiffness, damping, friction double stiffness; // stiffness coefficient @@ -630,7 +617,6 @@ typedef struct mjsWrap_ { // wrapping object specification typedef struct mjsActuator_ { // actuator specification mjsElement* element; // element type mjString* name; // name - mjString* classname; // class name // gain, bias mjtGain gaintype; // gain type @@ -674,7 +660,6 @@ typedef struct mjsActuator_ { // actuator specification typedef struct mjsSensor_ { // sensor specification mjsElement* element; // element type mjString* name; // name - mjString* classname; // class name // sensor definition mjtSensor type; // type of sensor diff --git a/introspect/structs.py b/introspect/structs.py index f24f8dd1b3..3361ba2812 100644 --- a/introspect/structs.py +++ b/introspect/structs.py @@ -8719,13 +8719,6 @@ ), doc='name', ), - StructFieldDecl( - name='classname', - type=PointerType( - inner_type=ValueType(name='mjString'), - ), - doc='class name', - ), StructFieldDecl( name='type', type=ValueType(name='mjtJoint'), @@ -8893,13 +8886,6 @@ ), doc='name', ), - StructFieldDecl( - name='classname', - type=PointerType( - inner_type=ValueType(name='mjString'), - ), - doc='classname', - ), StructFieldDecl( name='type', type=ValueType(name='mjtGeom'), @@ -9108,13 +9094,6 @@ ), doc='name', ), - StructFieldDecl( - name='classname', - type=PointerType( - inner_type=ValueType(name='mjString'), - ), - doc='class name', - ), StructFieldDecl( name='pos', type=ArrayType( @@ -9212,13 +9191,6 @@ ), doc='name', ), - StructFieldDecl( - name='classname', - type=PointerType( - inner_type=ValueType(name='mjString'), - ), - doc='class name', - ), StructFieldDecl( name='pos', type=ArrayType( @@ -9358,13 +9330,6 @@ ), doc='name', ), - StructFieldDecl( - name='classname', - type=PointerType( - inner_type=ValueType(name='mjString'), - ), - doc='class name', - ), StructFieldDecl( name='pos', type=ArrayType( @@ -9483,13 +9448,6 @@ ), doc='name', ), - StructFieldDecl( - name='classname', - type=PointerType( - inner_type=ValueType(name='mjString'), - ), - doc='class name', - ), StructFieldDecl( name='contype', type=ValueType(name='int'), @@ -9665,13 +9623,6 @@ ), doc='name', ), - StructFieldDecl( - name='classname', - type=PointerType( - inner_type=ValueType(name='mjString'), - ), - doc='class name', - ), StructFieldDecl( name='content_type', type=PointerType( @@ -9862,13 +9813,6 @@ ), doc='name', ), - StructFieldDecl( - name='classname', - type=PointerType( - inner_type=ValueType(name='mjString'), - ), - doc='class name', - ), StructFieldDecl( name='file', type=PointerType( @@ -9985,13 +9929,6 @@ ), doc='name', ), - StructFieldDecl( - name='classname', - type=PointerType( - inner_type=ValueType(name='mjString'), - ), - doc='class name', - ), StructFieldDecl( name='type', type=ValueType(name='mjtTexture'), @@ -10121,13 +10058,6 @@ ), doc='name', ), - StructFieldDecl( - name='classname', - type=PointerType( - inner_type=ValueType(name='mjString'), - ), - doc='class name', - ), StructFieldDecl( name='texture', type=PointerType( @@ -10214,13 +10144,6 @@ ), doc='name', ), - StructFieldDecl( - name='classname', - type=PointerType( - inner_type=ValueType(name='mjString'), - ), - doc='class name', - ), StructFieldDecl( name='geomname1', type=PointerType( @@ -10352,13 +10275,6 @@ ), doc='name', ), - StructFieldDecl( - name='classname', - type=PointerType( - inner_type=ValueType(name='mjString'), - ), - doc='class name', - ), StructFieldDecl( name='type', type=ValueType(name='mjtEq'), @@ -10435,13 +10351,6 @@ ), doc='name', ), - StructFieldDecl( - name='classname', - type=PointerType( - inner_type=ValueType(name='mjString'), - ), - doc='class name', - ), StructFieldDecl( name='stiffness', type=ValueType(name='double'), @@ -10596,13 +10505,6 @@ ), doc='name', ), - StructFieldDecl( - name='classname', - type=PointerType( - inner_type=ValueType(name='mjString'), - ), - doc='class name', - ), StructFieldDecl( name='gaintype', type=ValueType(name='mjtGain'), @@ -10793,13 +10695,6 @@ ), doc='name', ), - StructFieldDecl( - name='classname', - type=PointerType( - inner_type=ValueType(name='mjString'), - ), - doc='class name', - ), StructFieldDecl( name='type', type=ValueType(name='mjtSensor'), diff --git a/src/user/user_mesh.cc b/src/user/user_mesh.cc index e83660e3ce..39f9e18c93 100644 --- a/src/user/user_mesh.cc +++ b/src/user/user_mesh.cc @@ -195,7 +195,6 @@ mjCMesh& mjCMesh::operator=(const mjCMesh& other) { void mjCMesh::PointToLocal() { spec.element = static_cast(this); spec.name = &name; - spec.classname = &classname; spec.file = &spec_file_; spec.content_type = &spec_content_type_; spec.uservert = &spec_vert_; @@ -1982,7 +1981,6 @@ mjCSkin& mjCSkin::operator=(const mjCSkin& other) { void mjCSkin::PointToLocal() { spec.element = static_cast(this); spec.name = &name; - spec.classname = &classname; spec.file = &spec_file_; spec.material = &spec_material_; spec.vert = &spec_vert_; @@ -2394,7 +2392,6 @@ mjCFlex& mjCFlex::operator=(const mjCFlex& other) { void mjCFlex::PointToLocal() { spec.element = static_cast(this); spec.name = &name; - spec.classname = &classname; spec.material = &spec_material_; spec.vertbody = &spec_vertbody_; spec.vert = &spec_vert_; diff --git a/src/user/user_objects.cc b/src/user/user_objects.cc index 4f10402a0d..76a6179f76 100644 --- a/src/user/user_objects.cc +++ b/src/user/user_objects.cc @@ -1686,6 +1686,7 @@ mjCJoint::mjCJoint(mjCModel* _model, mjCDef* _def) { // set model, def model = _model; def = (_def ? _def : (_model ? _model->Defaults(0) : 0)); + classname = def ? def->name : ""; // point to local PointToLocal(); @@ -1726,7 +1727,6 @@ bool mjCJoint::is_actfrclimited() const { return islimited(actfrclimited, actfrc void mjCJoint::PointToLocal() { spec.element = static_cast(this); spec.name = &name; - spec.classname = &classname; spec.userdata = &spec_userdata_; spec.info = &info; } @@ -1894,6 +1894,7 @@ mjCGeom::mjCGeom(mjCModel* _model, mjCDef* _def) { // set model, def model = _model; def = (_def ? _def : (_model ? _model->Defaults(0) : 0)); + classname = def ? def->name : ""; // point to local PointToLocal(); @@ -1927,7 +1928,6 @@ void mjCGeom::PointToLocal(void) { spec.element = static_cast(this); spec.name = &name; spec.info = &info; - spec.classname = &classname; spec.userdata = &spec_userdata_; spec.material = &spec_material_; spec.meshname = &spec_meshname_; @@ -2537,6 +2537,7 @@ mjCSite::mjCSite(mjCModel* _model, mjCDef* _def) { // set model, def model = _model; def = (_def ? _def : (_model ? _model->Defaults(0) : 0)); + classname = def ? def->name : ""; } @@ -2563,7 +2564,6 @@ void mjCSite::PointToLocal() { spec.element = static_cast(this); spec.name = &name; spec.info = &info; - spec.classname = &classname; spec.material = &spec_material_; spec.userdata = &spec_userdata_; } @@ -2683,6 +2683,7 @@ mjCCamera::mjCCamera(mjCModel* _model, mjCDef* _def) { // set model, def model = _model; def = (_def ? _def : (_model ? _model->Defaults(0) : 0)); + classname = def ? def->name : ""; // point to local PointToLocal(); @@ -2714,7 +2715,6 @@ mjCCamera& mjCCamera::operator=(const mjCCamera& other) { void mjCCamera::PointToLocal() { spec.element = static_cast(this); spec.name = &name; - spec.classname = &classname; spec.userdata = &spec_userdata_; spec.targetbody = &spec_targetbody_; spec.info = &info; @@ -2837,6 +2837,7 @@ mjCLight::mjCLight(mjCModel* _model, mjCDef* _def) { // set model, def model = _model; def = (_def ? _def : (_model ? _model->Defaults(0) : 0)); + classname = def ? def->name : ""; PointToLocal(); CopyFromSpec(); @@ -2865,7 +2866,6 @@ mjCLight& mjCLight::operator=(const mjCLight& other) { void mjCLight::PointToLocal() { spec.element = static_cast(this); spec.name = &name; - spec.classname = &classname; spec.targetbody = &spec_targetbody_; spec.info = &info; } @@ -3194,7 +3194,6 @@ mjCTexture& mjCTexture::operator=(const mjCTexture& other) { void mjCTexture::PointToLocal() { spec.element = static_cast(this); spec.name = &name; - spec.classname = &classname; spec.file = &spec_file_; spec.content_type = &spec_content_type_; spec.cubefiles = &spec_cubefiles_; @@ -3873,6 +3872,7 @@ mjCMaterial::mjCMaterial(mjCModel* _model, mjCDef* _def) { model = _model; def = (_def ? _def : (_model ? _model->Defaults(0) : 0)); + classname = def ? def->name : ""; PointToLocal(); @@ -3903,7 +3903,6 @@ mjCMaterial& mjCMaterial::operator=(const mjCMaterial& other) { void mjCMaterial::PointToLocal() { spec.element = static_cast(this); spec.name = &name; - spec.classname = &classname; spec.texture = &spec_texture_; spec.info = &info; } @@ -3960,6 +3959,7 @@ mjCPair::mjCPair(mjCModel* _model, mjCDef* _def) { // set model, def model = _model; def = (_def ? _def : (_model ? _model->Defaults(0) : 0)); + classname = def ? def->name : ""; // point to local PointToLocal(); @@ -3993,7 +3993,6 @@ mjCPair& mjCPair::operator=(const mjCPair& other) { void mjCPair::PointToLocal() { spec.element = static_cast(this); spec.name = &name; - spec.classname = &classname; spec.geomname1 = &spec_geomname1_; spec.geomname2 = &spec_geomname2_; spec.info = &info; @@ -4321,6 +4320,7 @@ mjCEquality::mjCEquality(mjCModel* _model, mjCDef* _def) { // set model, def model = _model; def = (_def ? _def : (_model ? _model->Defaults(0) : 0)); + classname = def ? def->name : ""; // point to local PointToLocal(); @@ -4352,7 +4352,6 @@ mjCEquality& mjCEquality::operator=(const mjCEquality& other) { void mjCEquality::PointToLocal() { spec.element = static_cast(this); spec.name = &name; - spec.classname = &classname; spec.name1 = &spec_name1_; spec.name2 = &spec_name2_; spec.info = &info; @@ -4483,6 +4482,7 @@ mjCTendon::mjCTendon(mjCModel* _model, mjCDef* _def) { // set model, def model = _model; def = (_def ? _def : (_model ? _model->Defaults(0) : 0)); + classname = def ? def->name : ""; // point to local PointToLocal(); @@ -4521,7 +4521,6 @@ bool mjCTendon::is_limited() const { return islimited(limited, range); } void mjCTendon::PointToLocal() { spec.element = static_cast(this); spec.name = &name; - spec.classname = &classname; spec.material = &spec_material_; spec.userdata = &spec_userdata_; spec.info = &info; @@ -4961,6 +4960,7 @@ mjCActuator::mjCActuator(mjCModel* _model, mjCDef* _def) { // set model, def model = _model; def = (_def ? _def : (_model ? _model->Defaults(0) : 0)); + classname = def ? def->name : ""; // in case this actuator is not compiled CopyFromSpec(); @@ -5002,7 +5002,6 @@ bool mjCActuator::is_actlimited() const { return islimited(actlimited, actrange) void mjCActuator::PointToLocal() { spec.element = static_cast(this); spec.name = &name; - spec.classname = &classname; spec.userdata = &spec_userdata_; spec.target = &spec_target_; spec.refsite = &spec_refsite_; @@ -5325,7 +5324,6 @@ mjCSensor& mjCSensor::operator=(const mjCSensor& other) { void mjCSensor::PointToLocal() { spec.element = static_cast(this); spec.name = &name; - spec.classname = &classname; spec.userdata = &spec_userdata_; spec.objname = &spec_objname_; spec.refname = &spec_refname_; diff --git a/src/user/user_objects.h b/src/user/user_objects.h index 9c50b48367..e6545e5776 100644 --- a/src/user/user_objects.h +++ b/src/user/user_objects.h @@ -300,7 +300,6 @@ class mjCBody : public mjCBody_, private mjsBody { // inherited using mjCBase::name; - using mjCBase::classname; using mjCBase::info; // used by mjXWriter and mjCModel @@ -362,7 +361,6 @@ class mjCFrame : public mjCFrame_, private mjsFrame { mjsFrame spec; using mjCBase::name; - using mjCBase::classname; using mjCBase::info; void CopyFromSpec(void); @@ -409,7 +407,6 @@ class mjCJoint : public mjCJoint_, private mjsJoint { mjsJoint spec; using mjCBase::name; - using mjCBase::classname; using mjCBase::info; void CopyFromSpec(void); @@ -510,7 +507,6 @@ class mjCGeom : public mjCGeom_, private mjsGeom { void NameSpace(const mjCModel* m); // inherited - using mjCBase::classname; using mjCBase::info; }; @@ -548,7 +544,6 @@ class mjCSite : public mjCSite_, private mjsSite { // use strings from mjCBase rather than mjStrings from mjsSite using mjCBase::name; - using mjCBase::classname; using mjCBase::info; // used by mjXWriter and mjCModel @@ -591,7 +586,6 @@ class mjCCamera : public mjCCamera_, private mjsCamera { mjsCamera spec; using mjCBase::name; - using mjCBase::classname; using mjCBase::info; // used by mjXWriter and mjCModel @@ -631,7 +625,6 @@ class mjCLight : public mjCLight_, private mjsLight { mjsLight spec; using mjCBase::name; - using mjCBase::classname; using mjCBase::info; // used by mjXWriter and mjCModel @@ -694,7 +687,6 @@ class mjCFlex: public mjCFlex_, private mjsFlex { mjsFlex spec; using mjCBase::name; - using mjCBase::classname; using mjCBase::info; void CopyFromSpec(void); @@ -794,7 +786,6 @@ class mjCMesh: public mjCMesh_, private mjsMesh { mjsMesh spec; using mjCBase::name; - using mjCBase::classname; using mjCBase::info; void CopyFromSpec(void); @@ -925,7 +916,6 @@ class mjCSkin: public mjCSkin_, private mjsSkin { mjsSkin spec; using mjCBase::name; - using mjCBase::classname; using mjCBase::info; const std::string& get_file() const { return file_; } @@ -1027,7 +1017,6 @@ class mjCTexture : public mjCTexture_, private mjsTexture { mjsTexture spec; using mjCBase::name; - using mjCBase::classname; using mjCBase::info; void CopyFromSpec(void); @@ -1082,7 +1071,6 @@ class mjCMaterial : public mjCMaterial_, private mjsMaterial { mjsMaterial spec; using mjCBase::name; - using mjCBase::classname; using mjCBase::info; void CopyFromSpec(); @@ -1123,7 +1111,6 @@ class mjCPair : public mjCPair_, private mjsPair { mjsPair spec; using mjCBase::name; - using mjCBase::classname; using mjCBase::info; void CopyFromSpec(); @@ -1220,7 +1207,6 @@ class mjCEquality : public mjCEquality_, private mjsEquality { mjsEquality spec; using mjCBase::name; - using mjCBase::classname; using mjCBase::info; void CopyFromSpec(); @@ -1261,7 +1247,6 @@ class mjCTendon : public mjCTendon_, private mjsTendon { mjsTendon spec; using mjCBase::name; - using mjCBase::classname; using mjCBase::info; void set_material(std::string _material) { material_ = _material; } @@ -1394,7 +1379,6 @@ class mjCActuator : public mjCActuator_, private mjsActuator { mjsActuator spec; using mjCBase::name; - using mjCBase::classname; using mjCBase::info; // used by mjXWriter and mjCModel @@ -1453,7 +1437,6 @@ class mjCSensor : public mjCSensor_, private mjsSensor { mjsSensor spec; using mjCBase::name; - using mjCBase::classname; using mjCBase::info; // used by mjXWriter and mjCModel diff --git a/src/xml/xml_native_reader.cc b/src/xml/xml_native_reader.cc index 6e685c76cd..fd005c5e78 100644 --- a/src/xml/xml_native_reader.cc +++ b/src/xml/xml_native_reader.cc @@ -1289,16 +1289,13 @@ void mjXReader::Statistic(XMLElement* section) { // flex element parser void mjXReader::OneFlex(XMLElement* elem, mjsFlex* pflex) { - string text, name, classname, material; + string text, name, material; int n; // read attributes if (ReadAttrTxt(elem, "name", name)) { mjs_setString(pflex->name, name.c_str()); } - if (ReadAttrTxt(elem, "classname", classname)) { - mjs_setString(pflex->classname, classname.c_str()); - } if (ReadAttrTxt(elem, "material", material)) { mjs_setString(pflex->material, material.c_str()); } @@ -1364,15 +1361,12 @@ void mjXReader::OneFlex(XMLElement* elem, mjsFlex* pflex) { // mesh element parser void mjXReader::OneMesh(XMLElement* elem, mjsMesh* pmesh) { int n; - string text, name, classname, content_type; + string text, name, content_type; // read attributes if (ReadAttrTxt(elem, "name", name)) { mjs_setString(pmesh->name, name.c_str()); } - if (ReadAttrTxt(elem, "class", classname)) { - mjs_setString(pmesh->classname, classname.c_str()); - } if (ReadAttrTxt(elem, "content_type", content_type)) { mjs_setString(pmesh->content_type, content_type.c_str()); } @@ -1526,16 +1520,13 @@ void mjXReader::OneSkin(XMLElement* elem, mjsSkin* pskin) { // material element parser void mjXReader::OneMaterial(XMLElement* elem, mjsMaterial* pmat) { - string text, name, classname, texture; + string text, name, texture; int n; // read attributes if (ReadAttrTxt(elem, "name", name)) { mjs_setString(pmat->name, name.c_str()); } - if (ReadAttrTxt(elem, "class", classname)) { - mjs_setString(pmat->classname, classname.c_str()); - } if (ReadAttrTxt(elem, "texture", texture)) { mjs_setString(pmat->texture, texture.c_str()); } @@ -1559,7 +1550,7 @@ void mjXReader::OneMaterial(XMLElement* elem, mjsMaterial* pmat) { // joint element parser void mjXReader::OneJoint(XMLElement* elem, mjsJoint* pjoint) { - string text, name, classname; + string text, name; std::vector userdata; int n; @@ -1567,9 +1558,6 @@ void mjXReader::OneJoint(XMLElement* elem, mjsJoint* pjoint) { if (ReadAttrTxt(elem, "name", name)) { mjs_setString(pjoint->name, name.c_str()); } - if (ReadAttrTxt(elem, "class", classname)) { - mjs_setString(pjoint->classname, classname.c_str()); - } if (MapValue(elem, "type", &n, joint_map, joint_sz)) { pjoint->type = (mjtJoint)n; } @@ -1609,7 +1597,7 @@ void mjXReader::OneJoint(XMLElement* elem, mjsJoint* pjoint) { // geom element parser void mjXReader::OneGeom(XMLElement* elem, mjsGeom* pgeom) { - string text, name, classname; + string text, name; std::vector userdata; std::string hfieldname, meshname, material; int n; @@ -1618,9 +1606,6 @@ void mjXReader::OneGeom(XMLElement* elem, mjsGeom* pgeom) { if (ReadAttrTxt(elem, "name", name)) { mjs_setString(pgeom->name, name.c_str()); } - if (ReadAttrTxt(elem, "class", classname)) { - mjs_setString(pgeom->classname, classname.c_str()); - } if (MapValue(elem, "type", &n, geom_map, mjNGEOMTYPES)) { pgeom->type = (mjtGeom)n; } @@ -1685,7 +1670,7 @@ void mjXReader::OneGeom(XMLElement* elem, mjsGeom* pgeom) { // site element parser void mjXReader::OneSite(XMLElement* elem, mjsSite* site) { int n; - string text, name, classname; + string text, name; std::vector userdata; std::string material; @@ -1693,9 +1678,6 @@ void mjXReader::OneSite(XMLElement* elem, mjsSite* site) { if (ReadAttrTxt(elem, "name", name)) { mjs_setString(site->name, name.c_str()); } - if (ReadAttrTxt(elem, "class", classname)) { - mjs_setString(site->classname, classname.c_str()); - } if (MapValue(elem, "type", &n, geom_map, mjNGEOMTYPES)) { site->type = (mjtGeom)n; } @@ -1722,16 +1704,13 @@ void mjXReader::OneSite(XMLElement* elem, mjsSite* site) { // camera element parser void mjXReader::OneCamera(XMLElement* elem, mjsCamera* pcam) { int n; - string text, name, classname, targetbody; + string text, name, targetbody; std::vector userdata; // read attributes if (ReadAttrTxt(elem, "name", name)) { mjs_setString(pcam->name, name.c_str()); } - if (ReadAttrTxt(elem, "class", classname)) { - mjs_setString(pcam->classname, classname.c_str()); - } if (ReadAttrTxt(elem, "target", targetbody)) { mjs_setString(pcam->targetbody, targetbody.c_str()); } @@ -1780,15 +1759,12 @@ void mjXReader::OneCamera(XMLElement* elem, mjsCamera* pcam) { // light element parser void mjXReader::OneLight(XMLElement* elem, mjsLight* plight) { int n; - string text, name, classname, targetbody; + string text, name, targetbody; // read attributes if (ReadAttrTxt(elem, "name", name)) { mjs_setString(plight->name, name.c_str()); } - if (ReadAttrTxt(elem, "class", classname)) { - mjs_setString(plight->classname, classname.c_str()); - } if (ReadAttrTxt(elem, "target", targetbody)) { mjs_setString(plight->targetbody, targetbody.c_str()); } @@ -1822,13 +1798,10 @@ void mjXReader::OneLight(XMLElement* elem, mjsLight* plight) { // pair element parser void mjXReader::OnePair(XMLElement* elem, mjsPair* ppair) { - string text, name, classname, geomname1, geomname2; + string text, name, geomname1, geomname2; // regular only if (!readingdefaults) { - if (ReadAttrTxt(elem, "class", classname)) { - mjs_setString(ppair->classname, classname.c_str()); - } if (ReadAttrTxt(elem, "geom1", geomname1)) { mjs_setString(ppair->geomname1, geomname1.c_str()); } @@ -1858,7 +1831,7 @@ void mjXReader::OnePair(XMLElement* elem, mjsPair* ppair) { // equality element parser void mjXReader::OneEquality(XMLElement* elem, mjsEquality* pequality) { int n; - string text, name1, name2, name, classname; + string text, name1, name2, name; // read type (bad keywords already detected by schema) text = elem->Value(); @@ -1869,9 +1842,6 @@ void mjXReader::OneEquality(XMLElement* elem, mjsEquality* pequality) { if (ReadAttrTxt(elem, "name", name)) { mjs_setString(pequality->name, name.c_str()); } - if (ReadAttrTxt(elem, "class", classname)) { - mjs_setString(pequality->classname, classname.c_str()); - }; switch (pequality->type) { case mjEQ_CONNECT: @@ -1935,16 +1905,13 @@ void mjXReader::OneEquality(XMLElement* elem, mjsEquality* pequality) { // tendon element parser void mjXReader::OneTendon(XMLElement* elem, mjsTendon* pten) { - string text, name, classname, material; + string text, name, material; std::vector userdata; // read attributes if (ReadAttrTxt(elem, "name", name)) { mjs_setString(pten->name, name.c_str()); } - if (ReadAttrTxt(elem, "class", classname)) { - mjs_setString(pten->classname, classname.c_str()); - } ReadAttrInt(elem, "group", &pten->group); if (ReadAttrTxt(elem, "material", material)) { mjs_setString(pten->material, material.c_str()); @@ -1979,15 +1946,12 @@ void mjXReader::OneTendon(XMLElement* elem, mjsTendon* pten) { // actuator element parser void mjXReader::OneActuator(XMLElement* elem, mjsActuator* pact) { - string text, type, name, classname, target, slidersite, refsite; + string text, type, name, target, slidersite, refsite; // common attributes if (ReadAttrTxt(elem, "name", name)) { mjs_setString(pact->name, name.c_str()); } - if (ReadAttrTxt(elem, "class", classname)) { - mjs_setString(pact->classname, classname.c_str()); - } ReadAttrInt(elem, "group", &pact->group); MapValue(elem, "ctrllimited", &pact->ctrllimited, TFAuto_map, 3); MapValue(elem, "forcelimited", &pact->forcelimited, TFAuto_map, 3); diff --git a/src/xml/xml_native_writer.cc b/src/xml/xml_native_writer.cc index b3db60afa7..7b3bf798b6 100644 --- a/src/xml/xml_native_writer.cc +++ b/src/xml/xml_native_writer.cc @@ -18,6 +18,7 @@ #include #include #include +#include #include #include @@ -198,7 +199,9 @@ void mjXWriter::OneMesh(XMLElement* elem, const mjCMesh* pmesh, mjCDef* def) { // regular if (!writingdefaults) { WriteAttrTxt(elem, "name", pmesh->name); - WriteAttrTxt(elem, "class", pmesh->classname); + if (pmesh->classname != "main") { + WriteAttrTxt(elem, "class", pmesh->classname); + } WriteAttrTxt(elem, "content_type", pmesh->get_content_type()); WriteAttrTxt(elem, "file", pmesh->get_file()); @@ -295,7 +298,9 @@ void mjXWriter::OneMaterial(XMLElement* elem, const mjCMaterial* pmat, mjCDef* d // regular if (!writingdefaults) { WriteAttrTxt(elem, "name", pmat->name); - WriteAttrTxt(elem, "class", pmat->classname); + if (pmat->classname != "main") { + WriteAttrTxt(elem, "class", pmat->classname); + } } // defaults and regular @@ -316,13 +321,16 @@ void mjXWriter::OneMaterial(XMLElement* elem, const mjCMaterial* pmat, mjCDef* d // write joint -void mjXWriter::OneJoint(XMLElement* elem, const mjCJoint* pjoint, mjCDef* def) { +void mjXWriter::OneJoint(XMLElement* elem, const mjCJoint* pjoint, mjCDef* def, + std::string_view classname) { double zero = 0; // regular if (!writingdefaults) { WriteAttrTxt(elem, "name", pjoint->name); - WriteAttrTxt(elem, "class", pjoint->classname); + if (classname != pjoint->classname && pjoint->classname != "main") { + WriteAttrTxt(elem, "class", pjoint->classname); + } if (pjoint->type != mjJNT_FREE) { WriteAttr(elem, "pos", 3, pjoint->pos); } @@ -364,17 +372,18 @@ void mjXWriter::OneJoint(XMLElement* elem, const mjCJoint* pjoint, mjCDef* def) } } - - // write geom -void mjXWriter::OneGeom(XMLElement* elem, const mjCGeom* pgeom, mjCDef* def) { +void mjXWriter::OneGeom(XMLElement* elem, const mjCGeom* pgeom, mjCDef* def, + std::string_view classname) { double unitq[4] = {1, 0, 0, 0}; double mass = 0; // regular if (!writingdefaults) { WriteAttrTxt(elem, "name", pgeom->name); - WriteAttrTxt(elem, "class", pgeom->classname); + if (classname != pgeom->classname && pgeom->classname != "main") { + WriteAttrTxt(elem, "class", pgeom->classname); + } if (mjGEOMINFO[pgeom->type]) { WriteAttr(elem, "size", mjGEOMINFO[pgeom->type], pgeom->size, def->Geom().size); } @@ -459,16 +468,17 @@ void mjXWriter::OneGeom(XMLElement* elem, const mjCGeom* pgeom, mjCDef* def) { } } - - // write site -void mjXWriter::OneSite(XMLElement* elem, const mjCSite* psite, mjCDef* def) { +void mjXWriter::OneSite(XMLElement* elem, const mjCSite* psite, mjCDef* def, + std::string_view classname) { double unitq[4] = {1, 0, 0, 0}; // regular if (!writingdefaults) { WriteAttrTxt(elem, "name", psite->name); - WriteAttrTxt(elem, "class", psite->classname); + if (classname != psite->classname && psite->classname != "main") { + WriteAttrTxt(elem, "class", psite->classname); + } WriteAttr(elem, "pos", 3, psite->pos); WriteAttr(elem, "quat", 4, psite->quat, unitq); if (mjGEOMINFO[psite->type]) { @@ -494,16 +504,17 @@ void mjXWriter::OneSite(XMLElement* elem, const mjCSite* psite, mjCDef* def) { } } - - // write camera -void mjXWriter::OneCamera(XMLElement* elem, const mjCCamera* pcam, mjCDef* def) { +void mjXWriter::OneCamera(XMLElement* elem, const mjCCamera* pcam, mjCDef* def, + std::string_view classname) { double unitq[4] = {1, 0, 0, 0}; // regular if (!writingdefaults) { WriteAttrTxt(elem, "name", pcam->name); - WriteAttrTxt(elem, "class", pcam->classname); + if (classname != pcam->classname && pcam->classname != "main") { + WriteAttrTxt(elem, "class", pcam->classname); + } WriteAttrTxt(elem, "target", pcam->get_targetbody()); WriteAttr(elem, "pos", 3, pcam->pos); WriteAttr(elem, "quat", 4, pcam->quat, unitq); @@ -534,14 +545,15 @@ void mjXWriter::OneCamera(XMLElement* elem, const mjCCamera* pcam, mjCDef* def) } } - - // write light -void mjXWriter::OneLight(XMLElement* elem, const mjCLight* plight, mjCDef* def) { +void mjXWriter::OneLight(XMLElement* elem, const mjCLight* plight, mjCDef* def, + std::string_view classname) { // regular if (!writingdefaults) { WriteAttrTxt(elem, "name", plight->name); - WriteAttrTxt(elem, "class", plight->classname); + if (classname != plight->classname && plight->classname != "main") { + WriteAttrTxt(elem, "class", plight->classname); + } WriteAttrTxt(elem, "target", plight->get_targetbody()); WriteAttr(elem, "pos", 3, plight->pos); WriteAttr(elem, "dir", 3, plight->dir); @@ -561,13 +573,13 @@ void mjXWriter::OneLight(XMLElement* elem, const mjCLight* plight, mjCDef* def) WriteAttrKey(elem, "mode", camlight_map, camlight_sz, plight->mode, def->Light().mode); } - - // write pair void mjXWriter::OnePair(XMLElement* elem, const mjCPair* ppair, mjCDef* def) { // regular if (!writingdefaults) { - WriteAttrTxt(elem, "class", ppair->classname); + if (ppair->classname != "main") { + WriteAttrTxt(elem, "class", ppair->classname); + } WriteAttrTxt(elem, "geom1", ppair->get_geomname1()); WriteAttrTxt(elem, "geom2", ppair->get_geomname2()); } @@ -591,7 +603,9 @@ void mjXWriter::OneEquality(XMLElement* elem, const mjCEquality* peq, mjCDef* de // regular if (!writingdefaults) { WriteAttrTxt(elem, "name", peq->name); - WriteAttrTxt(elem, "class", peq->classname); + if (peq->classname != "main") { + WriteAttrTxt(elem, "class", peq->classname); + } switch (peq->type) { case mjEQ_CONNECT: @@ -644,7 +658,9 @@ void mjXWriter::OneTendon(XMLElement* elem, const mjCTendon* pten, mjCDef* def) // regular if (!writingdefaults) { WriteAttrTxt(elem, "name", pten->name); - WriteAttrTxt(elem, "class", pten->classname); + if (pten->classname != "main") { + WriteAttrTxt(elem, "class", pten->classname); + } } // defaults and regular @@ -691,7 +707,9 @@ void mjXWriter::OneActuator(XMLElement* elem, const mjCActuator* pact, mjCDef* d // regular if (!writingdefaults) { WriteAttrTxt(elem, "name", pact->name); - WriteAttrTxt(elem, "class", pact->classname); + if (pact->classname != "main") { + WriteAttrTxt(elem, "class", pact->classname); + } // transmission target switch (pact->trntype) { @@ -1515,7 +1533,7 @@ XMLElement* mjXWriter::OneFrame(XMLElement* elem, mjCFrame* frame) { // recursive body and frame writer -void mjXWriter::Body(XMLElement* elem, mjCBody* body) { +void mjXWriter::Body(XMLElement* elem, mjCBody* body, std::string_view childclass) { double unitq[4] = {1, 0, 0, 0}; if (!body) { @@ -1557,31 +1575,51 @@ void mjXWriter::Body(XMLElement* elem, mjCBody* body) { // write joints for (int i=0; ijoints.size(); i++) { XMLElement* celem = OneFrame(elem, body->joints[i]->frame); - OneJoint(InsertEnd(celem, "joint"), body->joints[i], body->joints[i]->def); + std::string classname = body->joints[i]->frame && !body->joints[i]->frame->classname.empty() + ? body->joints[i]->frame->classname + : body->classname; + OneJoint(InsertEnd(celem, "joint"), body->joints[i], body->joints[i]->def, + classname.empty() ? childclass : classname); } // write geoms for (int i=0; igeoms.size(); i++) { XMLElement* celem = OneFrame(elem, body->geoms[i]->frame); - OneGeom(InsertEnd(celem, "geom"), body->geoms[i], body->geoms[i]->def); + std::string classname = body->geoms[i]->frame && !body->geoms[i]->frame->classname.empty() + ? body->geoms[i]->frame->classname + : body->classname; + OneGeom(InsertEnd(celem, "geom"), body->geoms[i], body->geoms[i]->def, + classname.empty() ? childclass : classname); } // write sites for (int i=0; isites.size(); i++) { XMLElement* celem = OneFrame(elem, body->sites[i]->frame); - OneSite(InsertEnd(celem, "site"), body->sites[i], body->sites[i]->def); + std::string classname = body->sites[i]->frame && !body->sites[i]->frame->classname.empty() + ? body->sites[i]->frame->classname + : body->classname; + OneSite(InsertEnd(celem, "site"), body->sites[i], body->sites[i]->def, + classname.empty() ? childclass : classname); } // write cameras for (int i=0; icameras.size(); i++) { XMLElement* celem = OneFrame(elem, body->cameras[i]->frame); - OneCamera(InsertEnd(celem, "camera"), body->cameras[i], body->cameras[i]->def); + std::string classname = body->cameras[i]->frame && !body->cameras[i]->frame->classname.empty() + ? body->cameras[i]->frame->classname + : body->classname; + OneCamera(InsertEnd(celem, "camera"), body->cameras[i], body->cameras[i]->def, + classname.empty() ? childclass : classname); } // write lights for (int i=0; ilights.size(); i++) { XMLElement* celem = OneFrame(elem, body->lights[i]->frame); - OneLight(InsertEnd(celem, "light"), body->lights[i], body->lights[i]->def); + std::string classname = body->lights[i]->frame && !body->lights[i]->frame->classname.empty() + ? body->lights[i]->frame->classname + : body->classname; + OneLight(InsertEnd(celem, "light"), body->lights[i], body->lights[i]->def, + classname.empty() ? childclass : classname); } // write plugin @@ -1592,7 +1630,10 @@ void mjXWriter::Body(XMLElement* elem, mjCBody* body) { // write child bodies recursively for (int i=0; ibodies.size(); i++) { XMLElement* celem = OneFrame(elem, body->bodies[i]->frame); - Body(InsertEnd(celem, "body"), body->bodies[i]); + std::string classname = body->bodies[i]->frame && !body->bodies[i]->frame->classname.empty() + ? body->bodies[i]->frame->classname + : body->classname; + Body(InsertEnd(celem, "body"), body->bodies[i], classname.empty() ? childclass : classname); } } diff --git a/src/xml/xml_native_writer.h b/src/xml/xml_native_writer.h index c6791acd57..f0d6cceccd 100644 --- a/src/xml/xml_native_writer.h +++ b/src/xml/xml_native_writer.h @@ -17,6 +17,7 @@ #include #include +#include #include #include "user/user_objects.h" @@ -49,7 +50,6 @@ class mjXWriter : public mjXBase { void Extension(tinyxml2::XMLElement* root); // extension section void Custom(tinyxml2::XMLElement* root); // custom section void Asset(tinyxml2::XMLElement* root); // asset section - void Body(tinyxml2::XMLElement* elem, mjCBody* body); // body/world section void Contact(tinyxml2::XMLElement* root); // contact section void Deformable(tinyxml2::XMLElement* root); // deformable section void Equality(tinyxml2::XMLElement* root); // equality section @@ -58,16 +58,24 @@ class mjXWriter : public mjXBase { void Sensor(tinyxml2::XMLElement* root); // sensor section void Keyframe(tinyxml2::XMLElement* root); // keyframe section + // body/world section + void Body(tinyxml2::XMLElement* elem, mjCBody* body, std::string_view childclass = ""); + // single element writers, used in defaults and main body void OneFlex(tinyxml2::XMLElement* elem, const mjCFlex* pflex); void OneMesh(tinyxml2::XMLElement* elem, const mjCMesh* pmesh, mjCDef* def); void OneSkin(tinyxml2::XMLElement* elem, const mjCSkin* pskin); void OneMaterial(tinyxml2::XMLElement* elem, const mjCMaterial* pmaterial, mjCDef* def); - void OneJoint(tinyxml2::XMLElement* elem, const mjCJoint* pjoint, mjCDef* def); - void OneGeom(tinyxml2::XMLElement* elem, const mjCGeom* pgeom, mjCDef* def); - void OneSite(tinyxml2::XMLElement* elem, const mjCSite* psite, mjCDef* def); - void OneCamera(tinyxml2::XMLElement* elem, const mjCCamera* pcamera, mjCDef* def); - void OneLight(tinyxml2::XMLElement* elem, const mjCLight* plight, mjCDef* def); + void OneJoint(tinyxml2::XMLElement* elem, const mjCJoint* pjoint, mjCDef* def, + std::string_view classname = ""); + void OneGeom(tinyxml2::XMLElement* elem, const mjCGeom* pgeom, mjCDef* def, + std::string_view classname = ""); + void OneSite(tinyxml2::XMLElement* elem, const mjCSite* psite, mjCDef* def, + std::string_view classname = ""); + void OneCamera(tinyxml2::XMLElement* elem, const mjCCamera* pcamera, + mjCDef* def, std::string_view classname = ""); + void OneLight(tinyxml2::XMLElement* elem, const mjCLight* plight, mjCDef* def, + std::string_view classname = ""); void OnePair(tinyxml2::XMLElement* elem, const mjCPair* ppair, mjCDef* def); void OneEquality(tinyxml2::XMLElement* elem, const mjCEquality* pequality, mjCDef* def); void OneTendon(tinyxml2::XMLElement* elem, const mjCTendon* ptendon, mjCDef* def);