| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| |
|
| | #ifndef MUJOCO_SRC_USER_USER_MODEL_H_ |
| | #define MUJOCO_SRC_USER_USER_MODEL_H_ |
| |
|
| | #include <array> |
| | #include <cstdint> |
| | #include <functional> |
| | #include <map> |
| | #include <string> |
| | #include <string_view> |
| | #include <unordered_map> |
| | #include <utility> |
| | #include <vector> |
| |
|
| | #include <mujoco/mjdata.h> |
| | #include <mujoco/mjmodel.h> |
| | #include <mujoco/mjplugin.h> |
| | #include <mujoco/mjtnum.h> |
| | #include <mujoco/mjspec.h> |
| | #include "user/user_objects.h" |
| |
|
| | typedef std::map<std::string, int, std::less<> > mjKeyMap; |
| | typedef std::array<mjKeyMap, mjNOBJECT> mjListKeyMap; |
| |
|
| | typedef struct mjKeyInfo_ { |
| | std::string name; |
| | double time; |
| | bool qpos; |
| | bool qvel; |
| | bool act; |
| | bool ctrl; |
| | bool mpos; |
| | bool mquat; |
| | } mjKeyInfo; |
| |
|
| | class mjCModel_ : public mjsElement { |
| | public: |
| | |
| | std::string prefix; |
| | std::string suffix; |
| |
|
| | protected: |
| | bool compiled; |
| |
|
| | |
| | int nbody; |
| | int njnt; |
| | int ngeom; |
| | int nsite; |
| | int ncam; |
| | int nlight; |
| | int nflex; |
| | int nmesh; |
| | int nskin; |
| | int nhfield; |
| | int ntex; |
| | int nmat; |
| | int npair; |
| | int nexclude; |
| | int neq; |
| | int ntendon; |
| | int nsensor; |
| | int nnumeric; |
| | int ntext; |
| | int ntuple; |
| | int nmocap; |
| | int nplugin; |
| |
|
| | |
| | int nq; |
| | int nv; |
| | int nu; |
| | int na; |
| | int nbvh; |
| | int nbvhstatic; |
| | int nbvhdynamic; |
| | int noct; |
| | int nflexnode; |
| | int nflexvert; |
| | int nflexedge; |
| | int nflexelem; |
| | int nflexelemdata; |
| | int nflexelemedge; |
| | int nflexshelldata; |
| | int nflexevpair; |
| | int nflextexcoord; |
| | int nmeshvert; |
| | int nmeshnormal; |
| | int nmeshtexcoord; |
| | int nmeshface; |
| | int nmeshpoly; |
| | int nmeshgraph; |
| | int nmeshpolyvert; |
| | int nmeshpolymap; |
| | int nskinvert; |
| | int nskintexvert; |
| | int nskinface; |
| | int nskinbone; |
| | int nskinbonevert; |
| | int nhfielddata; |
| | int ntexdata; |
| | int nwrap; |
| | int nsensordata; |
| | int nnumericdata; |
| | int ntextdata; |
| | int ntupledata; |
| | int npluginattr; |
| | int nnames; |
| | int npaths; |
| | int nM; |
| | int nB; |
| | int nC; |
| | int nD; |
| | int nJmom; |
| |
|
| | |
| | double meaninertia_auto; |
| | double meanmass_auto; |
| | double meansize_auto; |
| | double extent_auto; |
| | double center_auto[3]; |
| |
|
| | |
| | std::vector<mjtNum> qpos0; |
| | std::vector<mjtNum> body_pos0; |
| | std::vector<mjtNum> body_quat0; |
| |
|
| | |
| | std::string comment_; |
| | std::string modelfiledir_; |
| | std::string modelname_; |
| | std::string meshdir_; |
| | std::string texturedir_; |
| | std::string spec_comment_; |
| | std::string spec_modelfiledir_; |
| | std::string spec_modelname_; |
| | std::string spec_meshdir_; |
| | std::string spec_texturedir_; |
| | }; |
| |
|
| | |
| | |
| | |
| | |
| | |
| | |
| | class mjCModel : public mjCModel_, private mjSpec { |
| | friend class mjCBase; |
| | friend class mjCBody; |
| | friend class mjCCamera; |
| | friend class mjCGeom; |
| | friend class mjCFlex; |
| | friend class mjCHField; |
| | friend class mjCFrame; |
| | friend class mjCJoint; |
| | friend class mjCEquality; |
| | friend class mjCMesh; |
| | friend class mjCSkin; |
| | friend class mjCSite; |
| | friend class mjCTendon; |
| | friend class mjCTexture; |
| | friend class mjCActuator; |
| | friend class mjCSensor; |
| | friend class mjCDef; |
| | friend class mjXReader; |
| | friend class mjXWriter; |
| |
|
| | public: |
| | mjCModel(); |
| | mjCModel(const mjCModel& other); |
| | ~mjCModel(); |
| | void CopyFromSpec(); |
| | void PointToLocal(); |
| |
|
| | mjCModel& operator=(const mjCModel& other); |
| | mjCModel& operator+=(const mjCModel& other); |
| | mjCModel& operator-=(const mjCBody& subtree); |
| | mjCModel& operator+=(mjCDef& subtree); |
| | mjCModel& operator-=(const mjCDef& subtree); |
| |
|
| | mjSpec spec; |
| |
|
| | mjModel* Compile(const mjVFS* vfs = nullptr, mjModel** m = nullptr); |
| | bool CopyBack(const mjModel*); |
| | void FuseStatic(); |
| | void FuseReindex(mjCBody* body); |
| |
|
| | |
| | mjCFlex* AddFlex(); |
| | mjCMesh* AddMesh(mjCDef* def = nullptr); |
| | mjCSkin* AddSkin(); |
| | mjCHField* AddHField(); |
| | mjCTexture* AddTexture(); |
| | mjCMaterial* AddMaterial(mjCDef* def = nullptr); |
| | mjCPair* AddPair(mjCDef* def = nullptr); |
| | mjCBodyPair* AddExclude(); |
| | mjCEquality* AddEquality(mjCDef* def = nullptr); |
| | mjCTendon* AddTendon(mjCDef* def = nullptr); |
| | mjCActuator* AddActuator(mjCDef* def = nullptr); |
| | mjCSensor* AddSensor(); |
| | mjCNumeric* AddNumeric(); |
| | mjCText* AddText(); |
| | mjCTuple* AddTuple(); |
| | mjCKey* AddKey(); |
| | mjCPlugin* AddPlugin(); |
| |
|
| | |
| | void AppendSpec(mjSpec* spec, const mjsCompiler* compiler = nullptr); |
| |
|
| | |
| | template <class T> void Delete(std::vector<T*>& elements, |
| | const std::vector<bool>& discard); |
| |
|
| | |
| | template <class T> void DeleteAll(std::vector<T*>& elements); |
| |
|
| | |
| | void operator-=(mjsElement* el); |
| |
|
| | |
| | void RemoveDefault(mjCDef* def); |
| |
|
| | |
| | int NumObjects(mjtObj type); |
| | mjCBase* GetObject(mjtObj type, int id); |
| | mjsElement* NextObject(mjsElement* object, mjtObj type = mjOBJ_UNKNOWN); |
| |
|
| | |
| | bool IsCompiled() const; |
| | const mjCError& GetError() const; |
| | void SetError(const mjCError& error) { errInfo = error; } |
| | mjCBody* GetWorld(); |
| | mjCDef* FindDefault(std::string name); |
| | mjCDef* AddDefault(std::string name, mjCDef* parent = nullptr); |
| | mjCBase* FindObject(mjtObj type, std::string name) const; |
| | mjCBase* FindTree(mjCBody* body, mjtObj type, std::string name); |
| | mjSpec* FindSpec(std::string name) const; |
| | mjSpec* FindSpec(const mjsCompiler* compiler_); |
| | void ActivatePlugin(const mjpPlugin* plugin, int slot); |
| |
|
| | |
| | template <class T> |
| | mjCBase* FindAsset(std::string_view name, const std::vector<T*>& list) const; |
| |
|
| | |
| | std::string get_meshdir() const { return meshdir_; } |
| | std::string get_texturedir() const { return texturedir_; } |
| |
|
| | mjCDef* Default() const { return defaults_[0]; } |
| | int NumDefaults() const { return defaults_.size(); } |
| |
|
| | const std::vector<std::pair<const mjpPlugin*, int>>& ActivePlugins() const { |
| | return active_plugins_; |
| | }; |
| |
|
| | const std::vector<mjCFlex*>& Flexes() const { return flexes_; } |
| | const std::vector<mjCMesh*>& Meshes() const {return meshes_; } |
| | const std::vector<mjCSkin*>& Skins() const { return skins_; } |
| | const std::vector<mjCHField*>& HFields() const { return hfields_; } |
| | const std::vector<mjCTexture*>& Textures() const { return textures_; } |
| | const std::vector<mjCMaterial*>& Materials() const { return materials_; } |
| | const std::vector<mjCPair*>& Pairs() const { return pairs_; } |
| | const std::vector<mjCBodyPair*>& Excludes() const { return excludes_; } |
| | const std::vector<mjCEquality*>& Equalities() const { return equalities_; } |
| | const std::vector<mjCTendon*>& Tendons() const { return tendons_; } |
| | const std::vector<mjCActuator*>& Actuators() const { return actuators_; } |
| | const std::vector<mjCSensor*>& Sensors() const { return sensors_; } |
| | const std::vector<mjCNumeric*>& Numerics() const { return numerics_; } |
| | const std::vector<mjCText*>& Texts() const { return texts_; } |
| | const std::vector<mjCTuple*>& Tuples() const { return tuples_; } |
| | const std::vector<mjCKey*>& Keys() const { return keys_; } |
| | const std::vector<mjCPlugin*>& Plugins() const { return plugins_; } |
| | const std::vector<mjCBody*>& Bodies() const { return bodies_; } |
| | const std::vector<mjCGeom*>& Geoms() const { return geoms_; } |
| |
|
| | |
| | void ResolvePlugin(mjCBase* obj, const std::string& plugin_name, |
| | const std::string& plugin_instance_name, |
| | mjCPlugin** plugin_instance); |
| |
|
| | |
| | void Clear(); |
| |
|
| | |
| | void CompileMeshes(const mjVFS* vfs); |
| |
|
| | |
| | template <class T> void DeleteMaterial(std::vector<T*>& list, |
| | std::string_view name = ""); |
| |
|
| | |
| | template <class T> |
| | void SaveState(const std::string& state_name, const T* qpos, const T* qvel, const T* act, |
| | const T* ctrl, const T* mpos, const T* mquat); |
| |
|
| | |
| | template <class T> |
| | void RestoreState(const std::string& state_name, const mjtNum* pos0, const mjtNum* mpos0, |
| | const mjtNum* mquat0, T* qpos, T* qvel, T* act, T* ctrl, T* mpos, T* mquat); |
| |
|
| | |
| | void MakeData(const mjModel* m, mjData** dest); |
| |
|
| | |
| | void StoreKeyframes(mjCModel* dest); |
| |
|
| | |
| | std::unordered_map<std::string, mjCDef*> def_map; |
| |
|
| | |
| | void SetDeepCopy(bool deepcopy) { deepcopy_ = deepcopy; } |
| |
|
| | |
| | void SetAttached(bool deepcopy) { attached_ |= !deepcopy; } |
| |
|
| | |
| | void CheckRepeat(mjtObj type); |
| |
|
| | private: |
| | |
| | std::vector<mjCDef*> defaults_; |
| |
|
| | |
| | std::vector<std::pair<const mjpPlugin*, int>> active_plugins_; |
| |
|
| | |
| | void MakeTreeLists(mjCBody* body = nullptr); |
| |
|
| | |
| | void TryCompile(mjModel*& m, mjData*& d, const mjVFS* vfs); |
| | void SetNuser(); |
| | void IndexAssets(bool discard); |
| | void CheckEmptyNames(); |
| | void SetSizes(); |
| | void AutoSpringDamper(mjModel*); |
| | void LengthRange(mjModel*, mjData*); |
| | void CopyNames(mjModel*); |
| | void CopyPaths(mjModel*); |
| | void CopyObjects(mjModel*); |
| | void CopyTree(mjModel*); |
| | void FinalizeSimple(mjModel* m); |
| | void CopyPlugins(mjModel*); |
| | int CountNJmom(const mjModel* m); |
| |
|
| | |
| | void RemovePlugins(); |
| |
|
| | |
| | std::vector<mjCFlex*> flexes_; |
| | std::vector<mjCMesh*> meshes_; |
| | std::vector<mjCSkin*> skins_; |
| | std::vector<mjCHField*> hfields_; |
| | std::vector<mjCTexture*> textures_; |
| | std::vector<mjCMaterial*> materials_; |
| | std::vector<mjCPair*> pairs_; |
| | std::vector<mjCBodyPair*> excludes_; |
| | std::vector<mjCEquality*> equalities_; |
| | std::vector<mjCTendon*> tendons_; |
| | std::vector<mjCActuator*> actuators_; |
| | std::vector<mjCSensor*> sensors_; |
| | std::vector<mjCNumeric*> numerics_; |
| | std::vector<mjCText*> texts_; |
| | std::vector<mjCTuple*> tuples_; |
| | std::vector<mjCKey*> keys_; |
| | std::vector<mjCPlugin*> plugins_; |
| | std::vector<mjSpec*> specs_; |
| |
|
| | |
| | std::vector<mjCBody*> bodies_; |
| | std::vector<mjCJoint*> joints_; |
| | std::vector<mjCGeom*> geoms_; |
| | std::vector<mjCSite*> sites_; |
| | std::vector<mjCCamera*> cameras_; |
| | std::vector<mjCLight*> lights_; |
| | std::vector<mjCFrame*> frames_; |
| |
|
| | |
| | std::array<std::vector<mjCBase*>*, mjNOBJECT> object_lists_; |
| |
|
| | |
| | template <class T> T* AddObject(std::vector<T*>& list, std::string type); |
| |
|
| | |
| | template <class T> T* AddObjectDefault(std::vector<T*>& list, std::string type, |
| | mjCDef* def); |
| |
|
| | |
| | template <class T> void CopyList(std::vector<T*>& dest, |
| | const std::vector<T*>& sources); |
| |
|
| | |
| | template <class T> void CopyExplicitPlugin(T* obj); |
| |
|
| | |
| | template <class T> void CopyPlugin(const std::vector<mjCPlugin*>& sources, |
| | const std::vector<T*>& list); |
| |
|
| | |
| | template <class T> void RemoveFromList(std::vector<T*>& list, const mjCModel& other); |
| |
|
| | |
| | void CreateObjectLists(); |
| |
|
| | |
| | void ProcessLists(bool checkrepeat = true); |
| |
|
| | |
| | template <class T> void ProcessList_(mjListKeyMap& ids, std::vector<T*>& list, |
| | mjtObj type, bool checkrepeat = true); |
| |
|
| | |
| | void ResetTreeLists(); |
| |
|
| | |
| | void SaveDofOffsets(bool computesize = false); |
| |
|
| | |
| | void ResolveKeyframes(const mjModel* m); |
| |
|
| | |
| | void ResizeKeyframe(mjCKey* key, const mjtNum* qpos0_, const mjtNum* bpos, const mjtNum* bquat); |
| |
|
| | |
| | void ComputeReference(); |
| |
|
| | |
| | bool CheckBodyMassInertia(mjCBody* body); |
| |
|
| | |
| | template <class T> |
| | void MarkPluginInstance(std::unordered_map<std::string, bool>& instances, |
| | const std::vector<T*>& list); |
| |
|
| | |
| | std::string PrintTree(const mjCBody* body, std::string indent = ""); |
| |
|
| | |
| | uint64_t Signature(); |
| |
|
| | |
| | template <class T> |
| | void ReassignChild(std::vector<T*>& dest, std::vector<T*>& list, mjCBody* parent, mjCBody* body); |
| |
|
| | |
| | template <class T> |
| | void ResolveReferences(std::vector<T*>& list, mjCBody* body = nullptr); |
| |
|
| | |
| | void DeleteSubtreePlugin(mjCBody* subtree); |
| |
|
| | mjListKeyMap ids; |
| | mjCError errInfo; |
| | std::vector<mjKeyInfo> key_pending_; |
| | bool deepcopy_; |
| | bool attached_ = false; |
| | std::unordered_map<const mjsCompiler*, mjSpec*> compiler2spec_; |
| | std::vector<mjCBase*> detached_; |
| | }; |
| | #endif |
| |
|