| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| |
|
| | #ifndef MUJOCO_SRC_USER_USER_OBJECTS_H_ |
| | #define MUJOCO_SRC_USER_USER_OBJECTS_H_ |
| |
|
| | #include <stdbool.h> |
| | #include <algorithm> |
| | #include <cstddef> |
| | #include <array> |
| | #include <functional> |
| | #include <map> |
| | #include <string> |
| | #include <string_view> |
| | #include <unordered_map> |
| | #include <utility> |
| | #include <vector> |
| |
|
| | #include <mujoco/mjmodel.h> |
| | #include <mujoco/mjplugin.h> |
| | #include <mujoco/mjspec.h> |
| | #include <mujoco/mjtnum.h> |
| | #include "user/user_cache.h" |
| | #include "user/user_util.h" |
| | #include <tiny_obj_loader.h> |
| |
|
| | using face_vertices_type = |
| | decltype(tinyobj::mesh_t::num_face_vertices)::value_type; |
| |
|
| | |
| | class mjCError; |
| | class mjCBase; |
| | class mjCBody; |
| | class mjCFrame; |
| | class mjCJoint; |
| | class mjCGeom; |
| | class mjCSite; |
| | class mjCCamera; |
| | class mjCLight; |
| | class mjCHField; |
| | class mjCFlex; |
| | class mjCMesh; |
| | class mjCSkin; |
| | class mjCTexture; |
| | class mjCMaterial; |
| | class mjCPair; |
| | class mjCBodyPair; |
| | class mjCEquality; |
| | class mjCTendon; |
| | class mjCWrap; |
| | class mjCActuator; |
| | class mjCSensor; |
| | class mjCNumeric; |
| | class mjCText; |
| | class mjCTuple; |
| | class mjCDef; |
| | class mjCModel; |
| | class mjXWriter; |
| | class mjXURDF; |
| |
|
| |
|
| | |
| |
|
| | |
| | const int mjGEOMINFO[mjNGEOMTYPES] = {3, 0, 1, 2, 3, 2, 3, 0}; |
| |
|
| | |
| | class [[nodiscard]] mjCError { |
| | public: |
| | mjCError(const mjCBase* obj = 0, |
| | const char* msg = 0, |
| | const char* str = 0, |
| | int pos1 = 0, |
| | int pos2 = 0); |
| |
|
| | char message[500]; |
| | bool warning; |
| | }; |
| |
|
| | |
| | const char* ResolveOrientation(double* quat, |
| | bool degree, |
| | const char* sequence, |
| | const mjsOrientation& orient); |
| |
|
| |
|
| | |
| |
|
| | |
| | class mjCBoundingVolume { |
| | public: |
| | mjCBoundingVolume(int id, int contype, int conaffinity, const double pos[3], |
| | const double quat[4], const double aabb[6]) : contype_(contype), |
| | conaffinity_(conaffinity), idval_(id) { |
| | std::copy(pos, pos + 3, pos_.begin()); |
| | std::copy(aabb, aabb + 6, aabb_.begin()); |
| | quat_set_ = quat != nullptr; |
| | if (quat_set_) { |
| | std::copy(quat, quat + 4, quat_.begin()); |
| | } |
| | } |
| |
|
| | mjCBoundingVolume(const int* id, int contype, int conaffinity, const double pos[3], |
| | const double quat[4], const double aabb[6]) : contype_(contype), |
| | conaffinity_(conaffinity), id_(id) { |
| | std::copy(pos, pos + 3, pos_.begin()); |
| | std::copy(aabb, aabb + 6, aabb_.begin()); |
| | quat_set_ = quat != nullptr; |
| | if (quat_set_) { |
| | std::copy(quat, quat + 4, quat_.begin()); |
| | } |
| | } |
| |
|
| | int Contype() const { return contype_; } |
| | int Conaffinity() const { return conaffinity_; } |
| | const double* AABB() const { return aabb_.data(); } |
| | double AABB(int i) const { return aabb_[i]; } |
| | const double* Pos() const { return pos_.data(); } |
| | double Pos(int i) const { return pos_[i]; } |
| | const double* Quat() const { return quat_set_ ? quat_.data() : nullptr; } |
| | const int* Id() const { return id_ ? id_ : &idval_; } |
| |
|
| | void SetContype(int val) { contype_ = val; } |
| | void SetConaffinity(int val) { conaffinity_ = val; } |
| | void SetAABB(const double* aabb) { std::copy(aabb, aabb + 6, aabb_.begin()); } |
| | void SetPos(const double* pos) { std::copy(pos, pos + 3, pos_.begin()); } |
| | void SetQuat(const double* quat) { |
| | quat_set_ = true; |
| | std::copy(quat, quat + 4, quat_.begin()); |
| | } |
| | void SetId(const int* id) { id_ = id; } |
| | void SetId(int val) { idval_ = val; } |
| |
|
| | private: |
| | int contype_; |
| | int conaffinity_; |
| | std::array<double, 6> aabb_; |
| | std::array<double, 3> pos_; |
| | std::array<double, 4> quat_; |
| | bool quat_set_; |
| | int idval_; |
| |
|
| | |
| | const int* id_ = nullptr; |
| | }; |
| |
|
| |
|
| | |
| | struct mjCBoundingVolumeHierarchy_ { |
| | protected: |
| | int nbvh_ = 0; |
| | std::vector<mjtNum> bvh_; |
| | std::vector<int> child_; |
| | std::vector<int> nodeid_; |
| | std::vector<int*> nodeidptr_; |
| | std::vector<int> level_; |
| | std::vector<mjCBoundingVolume> bvleaf_; |
| | std::string name_; |
| | double ipos_[3] = {0, 0, 0}; |
| | double iquat_[4] = {1, 0, 0, 0}; |
| | }; |
| |
|
| | class mjCBoundingVolumeHierarchy : public mjCBoundingVolumeHierarchy_ { |
| | public: |
| | |
| | void CreateBVH(); |
| | void Set(double ipos_element[3], double iquat_element[4]); |
| | void AllocateBoundingVolumes(int nleaf); |
| | void RemoveInactiveVolumes(int nmax); |
| | const mjCBoundingVolume* |
| | AddBoundingVolume(int id, int contype, int conaffinity, const double pos[3], |
| | const double quat[4], const double aabb[6]); |
| | const mjCBoundingVolume* |
| | AddBoundingVolume(const int* id, int contype, int conaffinity, const double pos[3], |
| | const double quat[4], const double aabb[6]); |
| |
|
| | |
| | int Nbvh() const { return nbvh_; } |
| | const std::vector<mjtNum>& Bvh() const { return bvh_; } |
| | const std::vector<int>& Child() const { return child_; } |
| | const std::vector<int>& Nodeid() const { return nodeid_; } |
| | int Nodeid(int id) const { return nodeid_[id]; } |
| | const int* Nodeidptr(int id) const { return nodeidptr_[id]; } |
| | const std::vector<int>& Level() const { return level_; } |
| | int Size() const { |
| | return sizeof(mjCBoundingVolume) * bvleaf_.size() |
| | + sizeof(mjtNum) * bvh_.size() + sizeof(int) * child_.size() |
| | + sizeof(int) * nodeid_.size() + sizeof(int) * level_.size(); |
| | } |
| |
|
| | private: |
| | |
| | struct BVElement { |
| | const mjCBoundingVolume* e; |
| | |
| | double lpos[3]; |
| | }; |
| | void Make(std::vector<BVElement>& elements); |
| | int MakeBVH(std::vector<BVElement>::iterator elements_begin, |
| | std::vector<BVElement>::iterator elements_end, int lev = 0); |
| | }; |
| |
|
| |
|
| |
|
| | |
| |
|
| | typedef std::array<std::array<double, 3>, 3> Triangle; |
| |
|
| | struct mjCOctree_ { |
| | int nnode_ = 0; |
| | std::vector<int> child_; |
| | std::vector<double> node_; |
| | std::vector<int> level_; |
| | std::vector<double> coeff_; |
| | std::vector<Triangle> face_; |
| | double ipos_[3] = {0, 0, 0}; |
| | double iquat_[4] = {1, 0, 0, 0}; |
| | }; |
| |
|
| | class mjCOctree : public mjCOctree_ { |
| | public: |
| | void CreateOctree(const double aamm[6]); |
| |
|
| | int NumNodes() const { return nnode_; } |
| | const std::vector<int>& Child() const { return child_; } |
| | const std::vector<double>& Nodes() const { return node_; } |
| | const std::vector<int>& Level() const { return level_; } |
| | void SetFace(const std::vector<double>& vert, const std::vector<int>& face); |
| | int Size() const { |
| | return sizeof(int) * child_.size() + sizeof(double) * node_.size() + |
| | sizeof(int) * level_.size() + sizeof(Triangle) * face_.size(); |
| | } |
| | void Clear() { |
| | child_.clear(); |
| | node_.clear(); |
| | level_.clear(); |
| | face_.clear(); |
| | } |
| | void AddCoeff(double coeff) { coeff_.push_back(coeff); } |
| | const std::vector<double>& Coeff() const { return coeff_; } |
| |
|
| | private: |
| | void Make(std::vector<Triangle>& elements); |
| | int MakeOctree(const std::vector<Triangle*>& elements, const double aamm[6], int lev = 0); |
| | }; |
| |
|
| |
|
| |
|
| | |
| | |
| |
|
| | class mjCBase_ : public mjsElement { |
| | public: |
| | int id; |
| | std::string name; |
| | std::string classname; |
| | std::string info; |
| | std::string prefix; |
| | std::string suffix; |
| | }; |
| |
|
| | class mjCBase : public mjCBase_ { |
| | friend class mjCDef; |
| |
|
| | public: |
| | |
| | static mjResource* LoadResource(const std::string& modelfiledir, |
| | const std::string& filename, const mjVFS* vfs); |
| |
|
| | |
| | |
| | static std::string GetAssetContentType(std::string_view resource_name, std::string_view raw_text); |
| |
|
| | |
| | void SetFrame(mjCFrame* _frame); |
| |
|
| | |
| | virtual void CopyFromSpec() {} |
| |
|
| | |
| | virtual void ResolveReferences(const mjCModel* m) {} |
| |
|
| | |
| | virtual void NameSpace(const mjCModel* m); |
| |
|
| | |
| | virtual void CopyPlugin() {} |
| |
|
| | |
| | virtual mjCBase* GetParent() const { return nullptr; } |
| |
|
| | |
| | mjCBase& operator=(const mjCBase& other); |
| |
|
| | mjCFrame* frame; |
| | mjCModel* model; |
| | mjsCompiler* compiler; |
| |
|
| | virtual ~mjCBase() = default; |
| |
|
| | |
| | virtual void ForgetKeyframes() {} |
| | virtual void ForgetKeyframes() const {} |
| |
|
| | |
| | |
| | |
| | virtual void AddRef() { ++refcount; } |
| | virtual int GetRef() { return refcount; } |
| | virtual void Release() { |
| | if (--refcount == 0) { |
| | delete this; |
| | } |
| | } |
| |
|
| | |
| | void SetUserValue(std::string_view key, const void* data, |
| | void (*cleanup)(const void*)); |
| | const void* GetUserValue(std::string_view key); |
| | void DeleteUserValue(std::string_view key); |
| |
|
| | protected: |
| | mjCBase(); |
| | mjCBase(const mjCBase& other); |
| |
|
| | |
| | int refcount = 1; |
| |
|
| | |
| | struct UserValue { |
| | const void* value = nullptr; |
| | void (*cleanup)(const void*) = nullptr; |
| |
|
| | UserValue() {} |
| | UserValue(const void* value, void (*cleanup)(const void*)) |
| | : value(value), cleanup(cleanup) {} |
| | UserValue(const UserValue& other) = delete; |
| | UserValue& operator=(const UserValue& other) = delete; |
| |
|
| | UserValue(UserValue&& other) : value(other.value), cleanup(other.cleanup) { |
| | other.value = nullptr; |
| | other.cleanup = nullptr; |
| | } |
| |
|
| | UserValue& operator=(UserValue&& other) { |
| | if (this != &other) { |
| | if (cleanup && value) { |
| | cleanup(value); |
| | } |
| | value = other.value; |
| | cleanup = other.cleanup; |
| | other.value = nullptr; |
| | other.cleanup = nullptr; |
| | } |
| | return *this; |
| | } |
| |
|
| | ~UserValue() { |
| | if (cleanup && value) { |
| | cleanup(value); |
| | } |
| | } |
| | }; |
| |
|
| | |
| | std::unordered_map<std::string, UserValue> user_payload_; |
| | }; |
| |
|
| |
|
| |
|
| | |
| | |
| |
|
| | class mjCBody_ : public mjCBase { |
| | protected: |
| | mjCBody* parent; |
| |
|
| | |
| | int weldid; |
| | int dofnum; |
| | int mocapid; |
| |
|
| | int contype; |
| | int conaffinity; |
| | double margin; |
| | double xpos0[3]; |
| | double xquat0[4]; |
| |
|
| | |
| | int lastdof; |
| | int subtreedofs; |
| |
|
| | mjCBoundingVolumeHierarchy tree; |
| |
|
| | |
| | std::string plugin_name; |
| | std::string plugin_instance_name; |
| | std::vector<double> userdata_; |
| | std::vector<double> spec_userdata_; |
| |
|
| | |
| | std::map<std::string, std::array<mjtNum, 3>> mpos_; |
| | std::map<std::string, std::array<mjtNum, 4>> mquat_; |
| | }; |
| |
|
| | class mjCBody : public mjCBody_, private mjsBody { |
| | friend class mjCJoint; |
| | friend class mjCGeom; |
| | friend class mjCSite; |
| | friend class mjCCamera; |
| | friend class mjCComposite; |
| | friend class mjCFrame; |
| | friend class mjCLight; |
| | friend class mjCFlex; |
| | friend class mjCFlexcomp; |
| | friend class mjCEquality; |
| | friend class mjCPair; |
| | friend class mjCModel; |
| | friend class mjXReader; |
| | friend class mjXWriter; |
| | friend class mjXURDF; |
| |
|
| | public: |
| | explicit mjCBody(mjCModel*); |
| | ~mjCBody(); |
| |
|
| | |
| | mjCBody* AddBody(mjCDef* = 0); |
| | mjCFrame* AddFrame(mjCFrame* = 0); |
| | mjCJoint* AddJoint(mjCDef* = 0); |
| | mjCJoint* AddFreeJoint(); |
| | mjCGeom* AddGeom(mjCDef* = 0); |
| | mjCSite* AddSite(mjCDef* = 0); |
| | mjCCamera* AddCamera(mjCDef* = 0); |
| | mjCLight* AddLight(mjCDef* = 0); |
| |
|
| | |
| | mjCBody& operator+=(const mjCBody& other); |
| | mjCBody& operator+=(const mjCFrame& other); |
| | mjCBody& operator-=(const mjCBody& subtree); |
| |
|
| | |
| | int NumObjects(mjtObj type); |
| | mjCBase* GetObject(mjtObj type, int id); |
| | mjCBase* FindObject(mjtObj type, std::string name, bool recursive = true); |
| |
|
| | |
| | void NameSpace(const mjCModel* m); |
| |
|
| | |
| | void MakeInertialExplicit(); |
| |
|
| | |
| | void ComputeBVH(); |
| |
|
| | |
| | mjsBody spec; |
| |
|
| | |
| | using mjCBase::info; |
| |
|
| | |
| | const std::vector<double>& get_userdata() { return userdata_; } |
| |
|
| | |
| | |
| | |
| | |
| | mjsElement* NextChild(const mjsElement* child, mjtObj type = mjOBJ_UNKNOWN, |
| | bool recursive = false); |
| |
|
| | |
| | void ForgetKeyframes() const; |
| |
|
| | |
| | mjCFrame* ToFrame(); |
| |
|
| | |
| | mjtNum* mpos(const std::string& state_name); |
| | mjtNum* mquat(const std::string& state_name); |
| |
|
| | mjsFrame* last_attached; |
| |
|
| | |
| | void SetParent(mjCBody* _body) { parent = _body; } |
| | mjCBody* GetParent() const { return parent; } |
| |
|
| | |
| | void SetModel(mjCModel* _model); |
| |
|
| | |
| | void ResetId(); |
| |
|
| | |
| | std::vector<mjCBody*> Bodies() const { return bodies; } |
| |
|
| | |
| | |
| | void AccumulateInertia(const mjsBody* other, mjsBody* result = nullptr); |
| |
|
| | private: |
| | mjCBody(const mjCBody& other, mjCModel* _model); |
| | mjCBody& operator=(const mjCBody& other); |
| |
|
| | void Compile(void); |
| | void InertiaFromGeom(void); |
| |
|
| | |
| | std::vector<mjCBody*> bodies; |
| | std::vector<mjCGeom*> geoms; |
| | std::vector<mjCFrame*> frames; |
| | std::vector<mjCJoint*> joints; |
| | std::vector<mjCSite*> sites; |
| | std::vector<mjCCamera*> cameras; |
| | std::vector<mjCLight*> lights; |
| |
|
| | void CopyFromSpec(); |
| | void PointToLocal(void); |
| | void NameSpace_(const mjCModel* m, bool propagate = true); |
| | void CopyPlugin(); |
| |
|
| | |
| | template <typename T> |
| | void CopyList(std::vector<T*>& dst, const std::vector<T*>& src, |
| | std::map<mjCFrame*, int>& fmap, const mjCFrame* pframe = nullptr); |
| |
|
| | |
| | template <class T> |
| | mjsElement* GetNext(const std::vector<T*>& list, const mjsElement* child); |
| |
|
| | bool IsAncestor(const mjCBody* child) const; |
| | }; |
| |
|
| |
|
| |
|
| | |
| | |
| |
|
| | class mjCFrame_ : public mjCBase { |
| | protected: |
| | bool compiled; |
| | }; |
| |
|
| | class mjCFrame : public mjCFrame_, private mjsFrame { |
| | friend class mjCBase; |
| | friend class mjCBody; |
| | friend class mjCGeom; |
| | friend class mjCJoint; |
| | friend class mjCSite; |
| | friend class mjCCamera; |
| | friend class mjCLight; |
| | friend class mjCModel; |
| |
|
| | public: |
| | mjCFrame(mjCModel* = 0, mjCFrame* = 0); |
| | mjCFrame(const mjCFrame& other); |
| | mjCFrame& operator=(const mjCFrame& other); |
| |
|
| | mjsFrame spec; |
| | using mjCBase::info; |
| |
|
| | void CopyFromSpec(void); |
| | void PointToLocal(void); |
| | void SetParent(mjCBody* _body) { body = _body; } |
| | mjCBody* GetParent() const { return body; } |
| |
|
| | mjCFrame& operator+=(const mjCBody& other); |
| |
|
| | bool IsAncestor(const mjCFrame* child) const; |
| |
|
| | mjsBody* last_attached; |
| |
|
| | private: |
| | void Compile(void); |
| |
|
| | mjCBody* body; |
| | }; |
| |
|
| |
|
| |
|
| | |
| | |
| |
|
| | class mjCJoint_ : public mjCBase { |
| | protected: |
| | mjCBody* body; |
| |
|
| | |
| | std::map<std::string, std::array<mjtNum, 7>> qpos_; |
| | std::map<std::string, std::array<mjtNum, 6>> qvel_; |
| |
|
| | |
| | std::vector<double> userdata_; |
| | std::vector<double> spec_userdata_; |
| | }; |
| |
|
| | class mjCJoint : public mjCJoint_, private mjsJoint { |
| | friend class mjCDef; |
| | friend class mjCEquality; |
| | friend class mjCBody; |
| | friend class mjCModel; |
| | friend class mjCSensor; |
| | friend class mjXWriter; |
| | friend class mjXURDF; |
| |
|
| | public: |
| | explicit mjCJoint(mjCModel* = nullptr, mjCDef* = nullptr); |
| | mjCJoint(const mjCJoint& other); |
| | mjCJoint& operator=(const mjCJoint& other); |
| |
|
| | mjsJoint spec; |
| | using mjCBase::info; |
| |
|
| | void CopyFromSpec(void); |
| | void SetParent(mjCBody* _body) { body = _body; } |
| | mjCBody* GetParent() const { return body; } |
| |
|
| | |
| | const std::vector<double>& get_userdata() const { return userdata_; } |
| | const double* get_range() const { return range; } |
| |
|
| | bool is_limited() const; |
| | bool is_actfrclimited() const; |
| |
|
| | static int nq(mjtJoint joint_type); |
| | static int nv(mjtJoint joint_type); |
| | int nq() const { return nq(spec.type); } |
| | int nv() const { return nv(spec.type); } |
| |
|
| | mjtNum* qpos(const std::string& state_name); |
| | mjtNum* qvel(const std::string& state_name); |
| |
|
| | private: |
| | int Compile(void); |
| | void PointToLocal(void); |
| |
|
| | |
| | int qposadr_; |
| | int dofadr_; |
| | }; |
| |
|
| |
|
| |
|
| | |
| | |
| |
|
| | class mjCGeom_ : public mjCBase { |
| | public: |
| | bool inferinertia; |
| |
|
| | protected: |
| | bool visual_; |
| | int matid; |
| | mjCMesh* mesh; |
| | mjCHField* hfield; |
| | double mass_; |
| | double inertia[3]; |
| | double aabb[6]; |
| | mjCBody* body; |
| | mjtNum fluid[mjNFLUID]; |
| |
|
| | |
| | std::string plugin_name; |
| | std::string plugin_instance_name; |
| | std::string hfieldname_; |
| | std::string meshname_; |
| | std::string material_; |
| | std::vector<double> userdata_; |
| | std::string spec_hfieldname_; |
| | std::string spec_meshname_; |
| | std::string spec_material_; |
| | std::vector<double> spec_userdata_; |
| | }; |
| |
|
| | class mjCGeom : public mjCGeom_, private mjsGeom { |
| | friend class mjCDef; |
| | friend class mjCMesh; |
| | friend class mjCPair; |
| | friend class mjCBody; |
| | friend class mjCModel; |
| | friend class mjCWrap; |
| | friend class mjXWriter; |
| | friend class mjXURDF; |
| |
|
| | public: |
| | explicit mjCGeom(mjCModel* = nullptr, mjCDef* = nullptr); |
| | mjCGeom(const mjCGeom& other); |
| | mjCGeom& operator=(const mjCGeom& other); |
| |
|
| | mjsGeom spec; |
| | double GetVolume() const; |
| | void SetInertia(void); |
| | bool IsVisual(void) const { return visual_; } |
| | void SetNotVisual(void) { visual_ = false; } |
| | void SetParent(mjCBody* _body) { body = _body; } |
| | mjCBody* GetParent() const { return body; } |
| | mjtGeom Type() const { return type; } |
| |
|
| | |
| | void SetFluidCoefs(void); |
| | |
| | double GetAddedMassKappa(double dx, double dy, double dz); |
| |
|
| | |
| | const std::vector<double>& get_userdata() const { return userdata_; } |
| | const std::string& get_hfieldname() const { return spec_hfieldname_; } |
| | const std::string& get_meshname() const { return spec_meshname_; } |
| | const std::string& get_material() const { return spec_material_; } |
| | void del_material() { spec_material_.clear(); } |
| |
|
| | private: |
| | void Compile(void); |
| | double GetRBound(void); |
| | void ComputeAABB(void); |
| | void CopyFromSpec(void); |
| | void PointToLocal(void); |
| | void NameSpace(const mjCModel* m); |
| | void CopyPlugin(); |
| |
|
| | |
| | using mjCBase::info; |
| | }; |
| |
|
| |
|
| |
|
| | |
| | |
| |
|
| | class mjCSite_ : public mjCBase { |
| | protected: |
| | |
| | std::string material_; |
| | std::vector<double> userdata_; |
| | std::string spec_material_; |
| | std::vector<double> spec_userdata_; |
| |
|
| | |
| | mjCBody* body; |
| | int matid; |
| | }; |
| |
|
| | class mjCSite : public mjCSite_, private mjsSite { |
| | friend class mjCDef; |
| | friend class mjCBody; |
| | friend class mjCModel; |
| | friend class mjXWriter; |
| | friend class mjXURDF; |
| |
|
| | public: |
| | explicit mjCSite(mjCModel* = nullptr, mjCDef* = nullptr); |
| | mjCSite(const mjCSite& other); |
| | mjCSite& operator=(const mjCSite& other); |
| |
|
| | mjsSite spec; |
| |
|
| | |
| | mjCBody* Body() const { return body; } |
| | void SetParent(mjCBody* _body) { body = _body; } |
| | mjCBody* GetParent() const { return body; } |
| |
|
| | |
| | using mjCBase::info; |
| |
|
| | |
| | const std::vector<double>& get_userdata() const { return userdata_; } |
| | const std::string& get_material() const { return material_; } |
| | void del_material() { material_.clear(); } |
| |
|
| | private: |
| | void Compile(void); |
| | void CopyFromSpec(); |
| | void PointToLocal(void); |
| | void NameSpace(const mjCModel* m); |
| | }; |
| |
|
| |
|
| |
|
| | |
| | |
| |
|
| | class mjCCamera_ : public mjCBase { |
| | protected: |
| | mjCBody* body; |
| | int targetbodyid; |
| | std::string targetbody_; |
| | std::string spec_targetbody_; |
| | std::vector<double> userdata_; |
| | std::vector<double> spec_userdata_; |
| | }; |
| |
|
| | class mjCCamera : public mjCCamera_, private mjsCamera { |
| | friend class mjCDef; |
| | friend class mjCBody; |
| | friend class mjCModel; |
| | friend class mjCSensor; |
| | friend class mjXWriter; |
| |
|
| | public: |
| | explicit mjCCamera(mjCModel* = nullptr, mjCDef* = nullptr); |
| | mjCCamera(const mjCCamera& other); |
| | mjCCamera& operator=(const mjCCamera& other); |
| |
|
| | mjsCamera spec; |
| | using mjCBase::info; |
| |
|
| | |
| | const std::string& get_targetbody() const { return targetbody_; } |
| | const std::vector<double>& get_userdata() const { return userdata_; } |
| |
|
| | void SetParent(mjCBody* _body) { body = _body; } |
| | mjCBody* GetParent() const { return body; } |
| |
|
| | private: |
| | void Compile(void); |
| | void CopyFromSpec(void); |
| | void PointToLocal(void); |
| | void NameSpace(const mjCModel* m); |
| | void ResolveReferences(const mjCModel* m); |
| | }; |
| |
|
| |
|
| |
|
| | |
| | |
| |
|
| | class mjCLight_ : public mjCBase { |
| | protected: |
| | mjCBody* body; |
| | int targetbodyid; |
| | int texid; |
| | std::string texture_; |
| | std::string spec_texture_; |
| | std::string targetbody_; |
| | std::string spec_targetbody_; |
| | }; |
| |
|
| | class mjCLight : public mjCLight_, private mjsLight { |
| | friend class mjCDef; |
| | friend class mjCBody; |
| | friend class mjCModel; |
| | friend class mjXWriter; |
| |
|
| | public: |
| | explicit mjCLight(mjCModel* = nullptr, mjCDef* = nullptr); |
| | mjCLight(const mjCLight& other); |
| | mjCLight& operator=(const mjCLight& other); |
| |
|
| | mjsLight spec; |
| | using mjCBase::info; |
| |
|
| | |
| | const std::string& get_targetbody() const { return targetbody_; } |
| | const std::string& get_texture() const { return texture_; } |
| |
|
| | void SetParent(mjCBody* _body) { body = _body; } |
| | mjCBody* GetParent() const { return body; } |
| |
|
| | private: |
| | void Compile(void); |
| | void CopyFromSpec(void); |
| | void PointToLocal(void); |
| | void NameSpace(const mjCModel* m); |
| | void ResolveReferences(const mjCModel* m); |
| | }; |
| |
|
| |
|
| |
|
| | |
| | |
| |
|
| | struct StencilFlap { |
| | static constexpr int kNumVerts = 4; |
| | int vertices[kNumVerts]; |
| | }; |
| |
|
| | class mjCFlex_ : public mjCBase { |
| | protected: |
| | int nvert; |
| | int nnode; |
| | int nedge; |
| | int nelem; |
| | int matid; |
| | bool rigid; |
| | bool centered; |
| | bool interpolated; |
| | std::vector<int> vertbodyid; |
| | std::vector<int> nodebodyid; |
| | std::vector<std::pair<int, int>> edge; |
| | std::vector<int> shell; |
| | std::vector<int> elemlayer; |
| | std::vector<int> evpair; |
| | std::vector<StencilFlap> flaps; |
| | std::vector<double> vertxpos; |
| | mjCBoundingVolumeHierarchy tree; |
| | std::vector<double> elemaabb_; |
| | std::vector<int> edgeidx_; |
| | std::vector<double> stiffness; |
| | std::vector<double> bending; |
| |
|
| | |
| | std::vector<std::string> vertbody_; |
| | std::vector<std::string> nodebody_; |
| | std::vector<double> vert_; |
| | std::vector<double> node_; |
| | std::vector<int> elem_; |
| | std::vector<float> texcoord_; |
| | std::vector<int> elemtexcoord_; |
| | std::string material_; |
| |
|
| | std::string spec_material_; |
| | std::vector<std::string> spec_vertbody_; |
| | std::vector<std::string> spec_nodebody_; |
| | std::vector<double> spec_vert_; |
| | std::vector<double> spec_node_; |
| | std::vector<int> spec_elem_; |
| | std::vector<float> spec_texcoord_; |
| | std::vector<int> spec_elemtexcoord_; |
| | }; |
| |
|
| | class mjCFlex: public mjCFlex_, private mjsFlex { |
| | friend class mjCDef; |
| | friend class mjCModel; |
| | friend class mjCFlexcomp; |
| | friend class mjCEquality; |
| | friend class mjXWriter; |
| |
|
| | public: |
| | explicit mjCFlex(mjCModel* = nullptr); |
| | mjCFlex(const mjCFlex& other); |
| | mjCFlex& operator=(const mjCFlex& other); |
| |
|
| | mjsFlex spec; |
| | using mjCBase::info; |
| |
|
| | void CopyFromSpec(void); |
| | void PointToLocal(void); |
| | void ResolveReferences(const mjCModel* m); |
| | void NameSpace(const mjCModel* m); |
| |
|
| | |
| | const std::string& get_material() const { return material_; } |
| | const std::vector<std::string>& get_vertbody() const { return vertbody_; } |
| | const std::vector<double>& get_vert() const { return vert_; } |
| | const std::vector<double>& get_elemaabb() const { return elemaabb_; } |
| | const std::vector<int>& get_elem() const { return elem_; } |
| | const std::vector<float>& get_texcoord() const { return texcoord_; } |
| | const std::vector<int>& get_elemtexcoord() const { return elemtexcoord_; } |
| | const std::vector<std::string>& get_nodebody() const { return nodebody_; } |
| |
|
| | bool HasTexcoord() const; |
| | void DelTexcoord(); |
| |
|
| | static constexpr int kNumEdges[3] = {1, 3, 6}; |
| |
|
| | private: |
| | void Compile(const mjVFS* vfs); |
| | void CreateBVH(void); |
| | void CreateShellPair(void); |
| |
|
| | std::vector<double> vert0_; |
| | std::vector<double> node0_; |
| | }; |
| |
|
| |
|
| |
|
| | |
| | |
| |
|
| | class mjCMesh_ : public mjCBase { |
| | protected: |
| | |
| | std::string plugin_name; |
| | std::string plugin_instance_name; |
| |
|
| | std::string content_type_ = ""; |
| | std::string file_; |
| | mjResource* resource_ = nullptr; |
| | std::vector<double> vert_; |
| | std::vector<float> normal_; |
| | std::vector<float> texcoord_; |
| | std::vector<int> face_; |
| | std::vector<int> facenormal_; |
| | std::vector<int> facetexcoord_; |
| |
|
| | std::string spec_content_type_; |
| | std::string spec_file_; |
| | std::vector<float> spec_vert_; |
| | std::vector<float> spec_normal_; |
| | std::vector<float> spec_texcoord_; |
| | std::vector<int> spec_face_; |
| | std::vector<int> spec_facenormal_; |
| | std::vector<int> spec_facetexcoord_; |
| |
|
| | |
| | bool needreorient_; |
| | bool needoct_; |
| | bool visual_; |
| | std::vector< std::pair<int, int> > halfedge_; |
| |
|
| | |
| | bool processed_; |
| | bool transformed_; |
| |
|
| | |
| | double pos_[3]; |
| | double quat_[4]; |
| | double boxsz_[3]; |
| | double aamm_[6]; |
| | double volume_; |
| | double surface_; |
| |
|
| | |
| | int szgraph_ = 0; |
| | bool needhull_; |
| | int maxhullvert_; |
| |
|
| | |
| | mjCBoundingVolumeHierarchy tree_; |
| | std::vector<double> face_aabb_; |
| |
|
| | |
| | mjCOctree octree_; |
| |
|
| | |
| | mujoco::user::FilePath modelfiledir_; |
| | mujoco::user::FilePath meshdir_; |
| | }; |
| |
|
| | class mjCMesh: public mjCMesh_, private mjsMesh { |
| | friend class mjCModel; |
| |
|
| | public: |
| | explicit mjCMesh(mjCModel* = nullptr, mjCDef* = nullptr); |
| | mjCMesh(const mjCMesh& other); |
| | mjCMesh& operator=(const mjCMesh& other); |
| | ~mjCMesh(); |
| |
|
| | mjsMesh spec; |
| | using mjCBase::info; |
| |
|
| | void CopyFromSpec(void); |
| | void PointToLocal(void); |
| | void NameSpace(const mjCModel* m); |
| |
|
| | |
| | const mjsPlugin& Plugin() const { return plugin; } |
| | const std::string& ContentType() const { return content_type_; } |
| | const std::string& File() const { return file_; } |
| | const double* Refpos() const { return refpos; } |
| | const double* Refquat() const { return refquat; } |
| | const double* Scale() const { return scale; } |
| | bool SmoothNormal() const { return smoothnormal; } |
| | const std::vector<double>& Vert() const { return vert_; } |
| | double Vert(int i) const { return vert_[i]; } |
| | const std::vector<float>& UserVert() const { return spec_vert_; } |
| | const std::vector<float>& UserNormal() const { return spec_normal_; } |
| | const std::vector<float>& Texcoord() const { return texcoord_; } |
| | const std::vector<int>& FaceTexcoord() const { return facetexcoord_; } |
| | const std::vector<float>& UserTexcoord() const { return spec_texcoord_; } |
| | const std::vector<int>& Face() const { return face_; } |
| | const std::vector<int>& UserFace() const { return spec_face_; } |
| | mjtMeshInertia Inertia() const { return spec.inertia; } |
| | |
| | void SetNeedHull(bool needhull) { needhull_ = needhull; } |
| |
|
| | |
| | const double* aamm() const { return aamm_; } |
| |
|
| | |
| | int nvert() const { return vert_.size()/3; } |
| | int nnormal() const { return normal_.size()/3; } |
| | int ntexcoord() const { return texcoord_.size()/2; } |
| | int nface() const { return face_.size()/3; } |
| | int npolygon() const { return polygons_.size(); } |
| | int npolygonvert() const { |
| | int acc = 0; |
| | for (const auto& polygon : polygons_) { |
| | acc += polygon.size(); |
| | } |
| | return acc; |
| | } |
| | int npolygonmap() const { |
| | int acc = 0; |
| | for (const auto& polygon : polygon_map_) { |
| | acc += polygon.size(); |
| | } |
| | return acc; |
| | } |
| |
|
| | |
| | int szgraph() const { return szgraph_; } |
| |
|
| | |
| | const mjCBoundingVolumeHierarchy& tree() { return tree_; } |
| |
|
| | |
| | const mjCOctree& octree() { return octree_; } |
| |
|
| | void Compile(const mjVFS* vfs); |
| | double* GetPosPtr(); |
| | double* GetQuatPtr(); |
| | double* GetInertiaBoxPtr(); |
| | double GetVolumeRef() const; |
| | void FitGeom(mjCGeom* geom, double* meshpos); |
| | bool HasTexcoord() const; |
| | void DelTexcoord(); |
| | bool IsVisual(void) const { return visual_; } |
| | void SetNotVisual(void) { visual_ = false; } |
| |
|
| | void CopyVert(float* arr) const; |
| | void CopyNormal(float* arr) const; |
| | void CopyFace(int* arr) const; |
| | void CopyFaceNormal(int* arr) const; |
| | void CopyFaceTexcoord(int* arr) const; |
| | void CopyTexcoord(float* arr) const; |
| | void CopyGraph(int* arr) const; |
| |
|
| | |
| | void CopyPolygons(int* verts, int* adr, int* num, int poly_adr) const; |
| |
|
| | |
| | void CopyPolygonMap(int *faces, int* adr, int* num, int poly_adr) const; |
| |
|
| | |
| | void CopyPolygonNormals(mjtNum* arr); |
| |
|
| | |
| | void SetBoundingVolume(int faceid); |
| |
|
| | |
| | void LoadFromResource(mjResource* resource, bool remove_repeated = false); |
| |
|
| | static bool IsObj(std::string_view filename, std::string_view ct = ""); |
| | static bool IsSTL(std::string_view filename, std::string_view ct = ""); |
| | static bool IsMSH(std::string_view filename, std::string_view ct = ""); |
| |
|
| | bool IsObj() const; |
| | bool IsSTL() const; |
| | bool IsMSH() const; |
| |
|
| | private: |
| | void TryCompile(const mjVFS* vfs); |
| |
|
| | |
| | bool LoadCachedMesh(mjCCache *cache, const mjResource* resource); |
| |
|
| | |
| | void CacheMesh(mjCCache *cache, const mjResource* resource); |
| |
|
| | |
| | void ProcessVertices(const std::vector<float>& vert, bool remove_repeated = false); |
| |
|
| |
|
| | void LoadOBJ(mjResource* resource, bool remove_repeated); |
| | void LoadSTL(mjResource* resource); |
| | void LoadMSH(mjResource* resource, bool remove_repeated); |
| |
|
| | void LoadSDF(); |
| | void MakeGraph(); |
| | void CopyGraph(); |
| | void MakeNormal(); |
| | void MakeCenter(); |
| | void Process(); |
| | void ApplyTransformations(); |
| | double ComputeFaceCentroid(double[3]) const; |
| | void CheckInitialMesh() const; |
| | void CopyPlugin(); |
| | void Rotate(double quat[4]); |
| | void Transform(double pos[3], double quat[4]); |
| | void MakePolygons(); |
| | void MakePolygonNormals(); |
| |
|
| | |
| | double ComputeInertia(double inert[6], const double CoM[3]) const; |
| |
|
| | int* GraphFaces() const { |
| | return graph_ + 2 + 3*(graph_[0] + graph_[1]); |
| | } |
| |
|
| | |
| | double* center_; |
| | int* graph_; |
| |
|
| | |
| | std::vector<std::vector<int>> polygons_; |
| | std::vector<double> polygon_normals_; |
| | std::vector<std::vector<int>> polygon_map_; |
| |
|
| | |
| | double ComputeVolume(double CoM[3], const double facecen[3]) const; |
| | |
| | double ComputeSurfaceArea(double CoM[3], const double facecen[3]) const; |
| | }; |
| |
|
| |
|
| |
|
| | |
| | |
| |
|
| | class mjCSkin_ : public mjCBase { |
| | protected: |
| | |
| | std::string file_; |
| | std::string material_; |
| | std::vector<float> vert_; |
| | std::vector<float> texcoord_; |
| | std::vector<int> face_; |
| | std::vector<std::string> bodyname_; |
| | std::vector<float> bindpos_; |
| | std::vector<float> bindquat_; |
| | std::vector<std::vector<int>> vertid_; |
| | std::vector<std::vector<float>> vertweight_; |
| |
|
| | std::string spec_file_; |
| | std::string spec_material_; |
| | std::vector<float> spec_vert_; |
| | std::vector<float> spec_texcoord_; |
| | std::vector<int> spec_face_; |
| | std::vector<std::string> spec_bodyname_; |
| | std::vector<float> spec_bindpos_; |
| | std::vector<float> spec_bindquat_; |
| | std::vector<std::vector<int>> spec_vertid_; |
| | std::vector<std::vector<float>> spec_vertweight_; |
| |
|
| | int matid; |
| | std::vector<int> bodyid; |
| |
|
| | |
| | mujoco::user::FilePath modelfiledir_; |
| | mujoco::user::FilePath meshdir_; |
| | }; |
| |
|
| | class mjCSkin: public mjCSkin_, private mjsSkin { |
| | friend class mjCModel; |
| | friend class mjXWriter; |
| |
|
| | public: |
| | explicit mjCSkin(mjCModel* = nullptr); |
| | mjCSkin(const mjCSkin& other); |
| | mjCSkin& operator=(const mjCSkin& other); |
| | ~mjCSkin(); |
| |
|
| | mjsSkin spec; |
| | using mjCBase::info; |
| |
|
| | const std::string& File() const { return file_; } |
| | const std::string& get_material() const { return material_; } |
| | const std::vector<float>& get_vert() const { return vert_; } |
| | const std::vector<float>& get_texcoord() const { return texcoord_; } |
| | const std::vector<int>& get_face() const { return face_; } |
| | const std::vector<std::string>& get_bodyname() const { return bodyname_; } |
| | const std::vector<float>& get_bindpos() const { return bindpos_; } |
| | const std::vector<float>& get_bindquat() const { return bindquat_; } |
| | const std::vector<std::vector<int>>& get_vertid() const { return vertid_; } |
| | const std::vector<std::vector<float>>& get_vertweight() const { return vertweight_; } |
| | void del_material() { material_.clear(); } |
| |
|
| | void CopyFromSpec(); |
| | void PointToLocal(); |
| |
|
| | private: |
| | void ResolveReferences(const mjCModel* m); |
| | void NameSpace(const mjCModel* m); |
| | void Compile(const mjVFS* vfs); |
| | void LoadSKN(mjResource* resource); |
| | }; |
| |
|
| |
|
| |
|
| | |
| | |
| |
|
| | class mjCHField_ : public mjCBase { |
| | protected: |
| | std::vector<float> data; |
| |
|
| | std::string file_; |
| | std::string content_type_; |
| | std::vector<float> userdata_; |
| | std::string spec_file_; |
| | std::string spec_content_type_; |
| | std::vector<float> spec_userdata_; |
| |
|
| | |
| | mujoco::user::FilePath modelfiledir_; |
| | mujoco::user::FilePath meshdir_; |
| | }; |
| |
|
| | class mjCHField : public mjCHField_, private mjsHField { |
| | friend class mjCGeom; |
| | friend class mjCModel; |
| | friend class mjXWriter; |
| |
|
| | public: |
| | explicit mjCHField(mjCModel* model); |
| | mjCHField(const mjCHField& other); |
| | mjCHField& operator=(const mjCHField& other); |
| | ~mjCHField(); |
| |
|
| | mjsHField spec; |
| | using mjCBase::info; |
| |
|
| | void CopyFromSpec(void); |
| | void PointToLocal(void); |
| | void NameSpace(const mjCModel* m); |
| |
|
| | std::string File() const { return file_; } |
| |
|
| | |
| | std::vector<float>& get_userdata() { return userdata_; } |
| |
|
| | private: |
| | void Compile(const mjVFS* vfs); |
| |
|
| | void LoadCustom(mjResource* resource); |
| | void LoadPNG(mjResource* resource); |
| | }; |
| |
|
| |
|
| |
|
| | |
| | |
| |
|
| | class mjCTexture_ : public mjCBase { |
| | protected: |
| | std::vector<std::byte> data_; |
| |
|
| | std::string file_; |
| | std::string content_type_; |
| | std::vector<std::string> cubefiles_; |
| | std::string spec_file_; |
| | std::string spec_content_type_; |
| | std::vector<std::string> spec_cubefiles_; |
| |
|
| | |
| | mujoco::user::FilePath modelfiledir_; |
| | mujoco::user::FilePath texturedir_; |
| | }; |
| |
|
| | class mjCTexture : public mjCTexture_, private mjsTexture { |
| | friend class mjCModel; |
| | friend class mjXReader; |
| | friend class mjXWriter; |
| |
|
| | public: |
| | explicit mjCTexture(mjCModel*); |
| | mjCTexture(const mjCTexture& other); |
| | mjCTexture& operator=(const mjCTexture& other); |
| | ~mjCTexture(); |
| |
|
| | mjsTexture spec; |
| | using mjCBase::info; |
| |
|
| | void CopyFromSpec(void); |
| | void PointToLocal(void); |
| | void NameSpace(const mjCModel* m); |
| |
|
| | std::string File() const { return file_; } |
| | std::string get_content_type() const { return content_type_; } |
| | std::vector<std::string> get_cubefiles() const { return cubefiles_; } |
| |
|
| | private: |
| | void Compile(const mjVFS* vfs); |
| |
|
| | void Builtin2D(void); |
| | void BuiltinCube(void); |
| | void Load2D(std::string filename, const mjVFS* vfs); |
| | void LoadCubeSingle(std::string filename, const mjVFS* vfs); |
| | void LoadCubeSeparate(const mjVFS* vfs); |
| |
|
| | void LoadFlip(std::string filename, const mjVFS* vfs, |
| | std::vector<unsigned char>& image, |
| | unsigned int& w, unsigned int& h, bool& is_srgb); |
| |
|
| | void LoadPNG(mjResource* resource, |
| | std::vector<unsigned char>& image, |
| | unsigned int& w, unsigned int& h, bool& is_srgb); |
| | void LoadKTX(mjResource* resource, |
| | std::vector<unsigned char>& image, |
| | unsigned int& w, unsigned int& h, bool& is_srgb); |
| | void LoadCustom(mjResource* resource, |
| | std::vector<unsigned char>& image, |
| | unsigned int& w, unsigned int& h, bool& is_srgb); |
| |
|
| | bool clear_data_; |
| | }; |
| |
|
| |
|
| |
|
| | |
| | |
| |
|
| | class mjCMaterial_ : public mjCBase { |
| | protected: |
| | int texid[mjNTEXROLE]; |
| | std::vector<std::string> textures_; |
| | std::vector<std::string> spec_textures_; |
| | }; |
| |
|
| | class mjCMaterial : public mjCMaterial_, private mjsMaterial { |
| | friend class mjCDef; |
| | friend class mjCModel; |
| | friend class mjXWriter; |
| |
|
| | public: |
| | explicit mjCMaterial(mjCModel* = nullptr, mjCDef* = nullptr); |
| | mjCMaterial(const mjCMaterial& other); |
| | mjCMaterial& operator=(const mjCMaterial& other); |
| |
|
| | mjsMaterial spec; |
| | using mjCBase::info; |
| |
|
| | void CopyFromSpec(); |
| | void PointToLocal(); |
| | void NameSpace(const mjCModel* m); |
| |
|
| | const std::string& get_texture(int i) const { return textures_[i]; } |
| | void del_textures() { for (auto& t : textures_) t.clear(); } |
| |
|
| | private: |
| | void Compile(void); |
| | }; |
| |
|
| |
|
| |
|
| | |
| | |
| |
|
| | class mjCPair_ : public mjCBase { |
| | protected: |
| | int signature; |
| | std::string geomname1_; |
| | std::string geomname2_; |
| | std::string spec_geomname1_; |
| | std::string spec_geomname2_; |
| | }; |
| |
|
| | class mjCPair : public mjCPair_, private mjsPair { |
| | friend class mjCDef; |
| | friend class mjCBody; |
| | friend class mjCModel; |
| | friend class mjXWriter; |
| |
|
| | public: |
| | explicit mjCPair(mjCModel* = nullptr, mjCDef* = nullptr); |
| | mjCPair(const mjCPair& other); |
| | mjCPair& operator=(const mjCPair& other); |
| |
|
| | mjsPair spec; |
| | using mjCBase::info; |
| |
|
| | void CopyFromSpec(); |
| | void PointToLocal(); |
| | void ResolveReferences(const mjCModel* m); |
| | void NameSpace(const mjCModel* m); |
| |
|
| | const std::string& get_geomname1() const { return geomname1_; } |
| | const std::string& get_geomname2() const { return geomname2_; } |
| |
|
| | int GetSignature(void) { |
| | return signature; |
| | } |
| |
|
| | private: |
| | void Compile(void); |
| |
|
| | mjCGeom* geom1; |
| | mjCGeom* geom2; |
| | }; |
| |
|
| |
|
| |
|
| | |
| | |
| |
|
| | class mjCBodyPair_ : public mjCBase { |
| | protected: |
| | int body1; |
| | int body2; |
| | int signature; |
| |
|
| | std::string bodyname1_; |
| | std::string bodyname2_; |
| | std::string spec_bodyname1_; |
| | std::string spec_bodyname2_; |
| | }; |
| |
|
| | class mjCBodyPair : public mjCBodyPair_, private mjsExclude { |
| | friend class mjCBody; |
| | friend class mjCModel; |
| |
|
| | public: |
| | explicit mjCBodyPair(mjCModel*); |
| | mjCBodyPair(const mjCBodyPair& other); |
| | mjCBodyPair& operator=(const mjCBodyPair& other); |
| |
|
| | mjsExclude spec; |
| | using mjCBase::info; |
| |
|
| | void CopyFromSpec(); |
| | void PointToLocal(); |
| | void ResolveReferences(const mjCModel* m); |
| | void NameSpace(const mjCModel* m); |
| |
|
| | std::string get_bodyname1() const { return bodyname1_; } |
| | std::string get_bodyname2() const { return bodyname2_; } |
| |
|
| | int GetSignature() { |
| | return signature; |
| | } |
| |
|
| | private: |
| | void Compile(); |
| | }; |
| |
|
| |
|
| |
|
| | |
| | |
| |
|
| | class mjCEquality_ : public mjCBase { |
| | protected: |
| | int obj1id; |
| | int obj2id; |
| | std::string name1_; |
| | std::string name2_; |
| | std::string spec_name1_; |
| | std::string spec_name2_; |
| | }; |
| |
|
| | class mjCEquality : public mjCEquality_, private mjsEquality { |
| | friend class mjCDef; |
| | friend class mjCBody; |
| | friend class mjCModel; |
| | friend class mjXWriter; |
| |
|
| | public: |
| | explicit mjCEquality(mjCModel* = 0, mjCDef* = 0); |
| | mjCEquality(const mjCEquality& other); |
| | mjCEquality& operator=(const mjCEquality& other); |
| |
|
| | mjsEquality spec; |
| | using mjCBase::info; |
| |
|
| | void CopyFromSpec(); |
| | void PointToLocal(); |
| | void ResolveReferences(const mjCModel* m); |
| | void NameSpace(const mjCModel* m); |
| |
|
| | private: |
| | void Compile(void); |
| | }; |
| |
|
| |
|
| |
|
| | |
| | |
| |
|
| | class mjCTendon_ : public mjCBase { |
| | protected: |
| | int matid; |
| |
|
| | |
| | std::string material_; |
| | std::string spec_material_; |
| | std::vector<double> userdata_; |
| | std::vector<double> spec_userdata_; |
| | }; |
| |
|
| | class mjCTendon : public mjCTendon_, private mjsTendon { |
| | friend class mjCDef; |
| | friend class mjCModel; |
| | friend class mjXWriter; |
| |
|
| | public: |
| | explicit mjCTendon(mjCModel* = nullptr, mjCDef* = nullptr); |
| | mjCTendon(const mjCTendon& other); |
| | mjCTendon& operator=(const mjCTendon& other); |
| | ~mjCTendon(); |
| |
|
| | mjsTendon spec; |
| | using mjCBase::info; |
| |
|
| | void set_material(std::string _material) { material_ = _material; } |
| | const std::string& get_material() const { return material_; } |
| | void del_material() { material_.clear(); } |
| |
|
| | |
| | void WrapSite(std::string wrapname, std::string_view wrapinfo = ""); |
| | void WrapGeom(std::string wrapname, std::string side, std::string_view wrapinfo = ""); |
| | void WrapJoint(std::string wrapname, double coef, std::string_view wrapinfo = ""); |
| | void WrapPulley(double divisor, std::string_view wrapinfo = ""); |
| |
|
| | |
| | int NumWraps() const; |
| | const mjCWrap* GetWrap(int i) const; |
| | std::vector<mjCWrap*> path; |
| |
|
| | |
| | const std::vector<double>& get_userdata() const { return userdata_; } |
| | const double* get_range() { return range; } |
| |
|
| | void CopyFromSpec(); |
| | void PointToLocal(); |
| | void ResolveReferences(const mjCModel* m); |
| | void NameSpace(const mjCModel* m); |
| | void SetModel(mjCModel* _model); |
| |
|
| | bool is_limited() const; |
| | bool is_actfrclimited() const; |
| |
|
| | private: |
| | void Compile(void); |
| | }; |
| |
|
| |
|
| |
|
| | |
| | |
| |
|
| | class mjCWrap_ : public mjCBase { |
| | public: |
| | mjtWrap type; |
| | int sideid; |
| | double prm; |
| | std::string sidesite; |
| | }; |
| |
|
| | class mjCWrap : public mjCWrap_, private mjsWrap { |
| | friend class mjCTendon; |
| | friend class mjCModel; |
| |
|
| | public: |
| | mjsWrap spec; |
| | using mjCBase::info; |
| |
|
| | void PointToLocal(); |
| | void ResolveReferences(const mjCModel* m); |
| | void NameSpace(const mjCModel* m); |
| |
|
| | mjCBase* obj; |
| |
|
| | private: |
| | mjCWrap(mjCModel*, mjCTendon*); |
| | mjCWrap(const mjCWrap& other); |
| | mjCWrap& operator=(const mjCWrap& other); |
| |
|
| | mjCTendon* tendon; |
| | }; |
| |
|
| |
|
| |
|
| | |
| | |
| |
|
| | class mjCPlugin_ : public mjCBase { |
| | public: |
| | int nstate; |
| | std::map<std::string, std::string, std::less<>> config_attribs; |
| | std::vector<char> flattened_attributes; |
| |
|
| | protected: |
| | std::string plugin_name; |
| | }; |
| |
|
| | class mjCPlugin : public mjCPlugin_ { |
| | friend class mjCModel; |
| | friend class mjXWriter; |
| |
|
| | public: |
| | explicit mjCPlugin(mjCModel*); |
| | mjCPlugin(const mjCPlugin& other); |
| | mjCPlugin& operator=(const mjCPlugin& other); |
| |
|
| | void PointToLocal(); |
| |
|
| | mjsPlugin spec; |
| | mjCBase* parent; |
| | int plugin_slot; |
| |
|
| | private: |
| | void Compile(void); |
| | }; |
| |
|
| |
|
| |
|
| | |
| | |
| |
|
| | class mjCActuator_ : public mjCBase { |
| | protected: |
| | int trnid[2]; |
| |
|
| | |
| | int actadr_; |
| | int actdim_; |
| | std::map<std::string, std::vector<mjtNum>> act_; |
| | std::map<std::string, mjtNum> ctrl_; |
| |
|
| | |
| | std::string plugin_name; |
| | std::string plugin_instance_name; |
| | std::string target_; |
| | std::string slidersite_; |
| | std::string refsite_; |
| | std::vector<double> userdata_; |
| | std::string spec_target_; |
| | std::string spec_slidersite_; |
| | std::string spec_refsite_; |
| | std::vector<double> spec_userdata_; |
| | }; |
| |
|
| | class mjCActuator : public mjCActuator_, private mjsActuator { |
| | friend class mjCDef; |
| | friend class mjCModel; |
| | friend class mjXWriter; |
| |
|
| | public: |
| | explicit mjCActuator(mjCModel* = nullptr, mjCDef* = nullptr); |
| | mjCActuator(const mjCActuator& other); |
| | mjCActuator& operator=(const mjCActuator& other); |
| |
|
| | mjsActuator spec; |
| | using mjCBase::info; |
| |
|
| | |
| | const std::vector<double>& get_userdata() const { return userdata_; } |
| | const std::string& get_target() const { return spec_target_; } |
| | const std::string& get_slidersite() const { return spec_slidersite_; } |
| | const std::string& get_refsite() const { return spec_refsite_; } |
| |
|
| | bool is_ctrllimited() const; |
| | bool is_forcelimited() const; |
| | bool is_actlimited() const; |
| |
|
| | std::vector<mjtNum>& act(const std::string& state_name); |
| | mjtNum& ctrl(const std::string& state_name); |
| |
|
| | private: |
| | void Compile(void); |
| | void CopyFromSpec(); |
| | void PointToLocal(); |
| | void ResolveReferences(const mjCModel* m); |
| | void NameSpace(const mjCModel* m); |
| | void CopyPlugin(); |
| |
|
| | |
| | void ForgetKeyframes(); |
| |
|
| | mjCBase* ptarget; |
| | }; |
| |
|
| |
|
| |
|
| | |
| | |
| |
|
| | class mjCSensor_ : public mjCBase { |
| | protected: |
| | |
| | std::string plugin_name; |
| | std::string plugin_instance_name; |
| | std::string objname_; |
| | std::string refname_; |
| | std::vector<double> userdata_; |
| | std::string spec_objname_; |
| | std::string spec_refname_; |
| | std::vector<double> spec_userdata_; |
| | }; |
| |
|
| | class mjCSensor : public mjCSensor_, private mjsSensor { |
| | friend class mjCDef; |
| | friend class mjCModel; |
| | friend class mjXWriter; |
| |
|
| | public: |
| | explicit mjCSensor(mjCModel*); |
| | mjCSensor(const mjCSensor& other); |
| | mjCSensor& operator=(const mjCSensor& other); |
| |
|
| | mjsSensor spec; |
| | using mjCBase::info; |
| |
|
| | |
| | const std::vector<double>& get_userdata() { return userdata_; } |
| | const std::string& get_objname() { return spec_objname_; } |
| | const std::string& get_refname() { return spec_refname_; } |
| |
|
| | private: |
| | void Compile(void); |
| | void CopyFromSpec(); |
| | void PointToLocal(); |
| | void ResolveReferences(const mjCModel* m); |
| | void NameSpace(const mjCModel* m); |
| | void CopyPlugin(); |
| |
|
| | mjCBase* obj; |
| | mjCBase* ref; |
| | }; |
| |
|
| |
|
| |
|
| | |
| | |
| |
|
| | class mjCNumeric_ : public mjCBase { |
| | protected: |
| | std::vector<double> data_; |
| | std::vector<double> spec_data_; |
| | }; |
| |
|
| | class mjCNumeric : public mjCNumeric_, private mjsNumeric { |
| | friend class mjCModel; |
| | friend class mjXWriter; |
| |
|
| | public: |
| | explicit mjCNumeric(mjCModel*); |
| | mjCNumeric(const mjCNumeric& other); |
| | mjCNumeric& operator=(const mjCNumeric& other); |
| | ~mjCNumeric(); |
| |
|
| | mjsNumeric spec; |
| | using mjCBase::info; |
| |
|
| | void PointToLocal(); |
| | void CopyFromSpec(); |
| |
|
| | private: |
| | void Compile(void); |
| | }; |
| |
|
| |
|
| |
|
| | |
| | |
| |
|
| | class mjCText_ : public mjCBase { |
| | protected: |
| | std::string data_; |
| | std::string spec_data_; |
| | }; |
| |
|
| | class mjCText : public mjCText_, private mjsText { |
| | friend class mjCModel; |
| | friend class mjXWriter; |
| |
|
| | public: |
| | explicit mjCText(mjCModel*); |
| | mjCText(const mjCText& other); |
| | mjCText& operator=(const mjCText& other); |
| | ~mjCText(); |
| |
|
| | mjsText spec; |
| | using mjCBase::info; |
| |
|
| | void PointToLocal(); |
| | void CopyFromSpec(); |
| |
|
| | private: |
| | void Compile(void); |
| | }; |
| |
|
| |
|
| |
|
| | |
| | |
| |
|
| | class mjCTuple_ : public mjCBase { |
| | protected: |
| | std::vector<mjCBase*> obj; |
| | std::vector<mjtObj> objtype_; |
| | std::vector<std::string> objname_; |
| | std::vector<double> objprm_; |
| | std::vector<mjtObj> spec_objtype_; |
| | std::vector<std::string> spec_objname_; |
| | std::vector<double> spec_objprm_; |
| | }; |
| |
|
| | class mjCTuple : public mjCTuple_, private mjsTuple { |
| | friend class mjCModel; |
| | friend class mjXWriter; |
| |
|
| | public: |
| | explicit mjCTuple(mjCModel*); |
| | mjCTuple(const mjCTuple& other); |
| | mjCTuple& operator=(const mjCTuple& other); |
| | ~mjCTuple(); |
| |
|
| | mjsTuple spec; |
| | using mjCBase::info; |
| |
|
| | void PointToLocal(); |
| | void CopyFromSpec(); |
| | void ResolveReferences(const mjCModel* m); |
| | void NameSpace(const mjCModel* m); |
| |
|
| | private: |
| | void Compile(void); |
| | }; |
| |
|
| |
|
| |
|
| | |
| | |
| |
|
| | class mjCKey_ : public mjCBase { |
| | protected: |
| | std::vector<double> qpos_; |
| | std::vector<double> qvel_; |
| | std::vector<double> act_; |
| | std::vector<double> mpos_; |
| | std::vector<double> mquat_; |
| | std::vector<double> ctrl_; |
| | std::vector<double> spec_qpos_; |
| | std::vector<double> spec_qvel_; |
| | std::vector<double> spec_act_; |
| | std::vector<double> spec_mpos_; |
| | std::vector<double> spec_mquat_; |
| | std::vector<double> spec_ctrl_; |
| | }; |
| |
|
| | class mjCKey : public mjCKey_, private mjsKey { |
| | friend class mjCModel; |
| | friend class mjXWriter; |
| |
|
| | public: |
| | explicit mjCKey(mjCModel*); |
| | mjCKey(const mjCKey& other); |
| | mjCKey& operator=(const mjCKey& other); |
| | ~mjCKey(); |
| |
|
| | mjsKey spec; |
| | using mjCBase::info; |
| |
|
| | void PointToLocal(); |
| | void CopyFromSpec(); |
| |
|
| | private: |
| | void Compile(const mjModel* m); |
| | }; |
| |
|
| |
|
| |
|
| | |
| | |
| |
|
| | class mjCDef : public mjsElement { |
| | friend class mjXWriter; |
| |
|
| | public: |
| | mjCDef(); |
| | explicit mjCDef(mjCModel*); |
| | mjCDef(const mjCDef& other); |
| | mjCDef& operator=(const mjCDef& other); |
| | mjCDef& operator+=(const mjCDef& other); |
| |
|
| | void CopyWithoutChildren(const mjCDef& other); |
| | void PointToLocal(void); |
| | void CopyFromSpec(void); |
| | void NameSpace(const mjCModel* m); |
| |
|
| | void Compile(const mjCModel* model); |
| |
|
| | |
| | mjCJoint& Joint() { return joint_; } |
| | mjCGeom& Geom() { return geom_; } |
| | mjCSite& Site() { return site_; } |
| | mjCCamera& Camera() { return camera_; } |
| | mjCLight& Light() { return light_; } |
| | mjCFlex& Flex() { return flex_; } |
| | mjCMesh& Mesh() { return mesh_; } |
| | mjCMaterial& Material() { return material_; } |
| | mjCPair& Pair() { return pair_; } |
| | mjCEquality& Equality() { return equality_; } |
| | mjCTendon& Tendon() { return tendon_; } |
| | mjCActuator& Actuator() { return actuator_; } |
| |
|
| | |
| | std::string name; |
| | int id; |
| | mjCDef* parent; |
| | std::vector<mjCDef*> child; |
| |
|
| | mjsDefault spec; |
| | mjCModel* model; |
| |
|
| | private: |
| | mjCJoint joint_; |
| | mjCGeom geom_; |
| | mjCSite site_; |
| | mjCCamera camera_; |
| | mjCLight light_; |
| | mjCFlex flex_; |
| | mjCMesh mesh_; |
| | mjCMaterial material_; |
| | mjCPair pair_; |
| | mjCEquality equality_; |
| | mjCTendon tendon_; |
| | mjCActuator actuator_; |
| | }; |
| |
|
| | #endif |
| |
|