| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| |
|
| | #ifndef MUJOCO_SRC_ENGINE_ENGINE_IO_H_ |
| | #define MUJOCO_SRC_ENGINE_ENGINE_IO_H_ |
| |
|
| | #include <mujoco/mjdata.h> |
| | #include <mujoco/mjexport.h> |
| | #include <mujoco/mjmodel.h> |
| | #include <mujoco/mjxmacro.h> |
| |
|
| | #ifdef __cplusplus |
| | #include <cstddef> |
| | extern "C" { |
| | #else |
| | #include <stddef.h> |
| | #endif |
| |
|
| | |
| | #define mjLOAD_MULTIPLE 2 |
| |
|
| | |
| |
|
| | |
| | MJAPI void mj_defaultLROpt(mjLROpt* opt); |
| |
|
| | |
| | MJAPI void mj_defaultSolRefImp(mjtNum* solref, mjtNum* solimp); |
| |
|
| | |
| | MJAPI void mj_defaultOption(mjOption* opt); |
| |
|
| | |
| | MJAPI void mj_defaultVisual(mjVisual* vis); |
| |
|
| | |
| | void mj_defaultStatistic(mjStatistic* stat); |
| |
|
| |
|
| | |
| |
|
| | |
| | void mj_makeModel(mjModel** dest, |
| | int nq, int nv, int nu, int na, int nbody, int nbvh, int nbvhstatic, int nbvhdynamic, int noct, |
| | int njnt, int ngeom, int nsite, int ncam, int nlight, int nflex, int nflexnode, int nflexvert, |
| | int nflexedge, int nflexelem, int nflexelemdata, int nflexelemedge, int nflexshelldata, |
| | int nflexevpair, int nflextexcoord, int nmesh, int nmeshvert, int nmeshnormal, |
| | int nmeshtexcoord, int nmeshface, int nmeshgraph, int nmeshpoly, int nmeshpolyvert, |
| | int nmeshpolymap, int nskin, int nskinvert, int nskintexvert, int nskinface, int nskinbone, |
| | int nskinbonevert, int nhfield, int nhfielddata, int ntex, int ntexdata, int nmat, int npair, |
| | int nexclude, int neq, int ntendon, int nwrap, int nsensor, int nnumeric, int nnumericdata, int ntext, |
| | int ntextdata, int ntuple, int ntupledata, int nkey, int nmocap, int nplugin, int npluginattr, |
| | int nuser_body, int nuser_jnt, int nuser_geom, int nuser_site, int nuser_cam, int nuser_tendon, |
| | int nuser_actuator, int nuser_sensor, int nnames, int npaths); |
| |
|
| | |
| | MJAPI mjModel* mj_copyModel(mjModel* dest, const mjModel* src); |
| |
|
| | |
| | MJAPI void mjv_copyModel(mjModel* dest, const mjModel* src); |
| |
|
| | |
| | MJAPI void mj_saveModel(const mjModel* m, const char* filename, void* buffer, int buffer_sz); |
| |
|
| | |
| | mjModel* mj_loadModelBuffer(const void* buffer, int buffer_sz); |
| |
|
| | |
| | MJAPI void mj_deleteModel(mjModel* m); |
| |
|
| | |
| | MJAPI int mj_sizeModel(const mjModel* m); |
| |
|
| | |
| | MJAPI const char* mj_validateReferences(const mjModel* m); |
| |
|
| |
|
| | |
| |
|
| | |
| | |
| | MJAPI mjData* mj_makeData(const mjModel* m); |
| |
|
| | |
| | MJAPI void mj_makeRawData(mjData** dest, const mjModel* m); |
| |
|
| | |
| | |
| | MJAPI mjData* mj_copyData(mjData* dest, const mjModel* m, const mjData* src); |
| |
|
| | |
| | MJAPI mjData* mjv_copyData(mjData* dest, const mjModel* m, const mjData* src); |
| |
|
| | |
| | MJAPI void mj_resetData(const mjModel* m, mjData* d); |
| |
|
| | |
| | MJAPI void mj_resetDataDebug(const mjModel* m, mjData* d, unsigned char debug_value); |
| |
|
| | |
| | MJAPI void mj_resetDataKeyframe(const mjModel* m, mjData* d, int key); |
| |
|
| | |
| | MJAPI void* mj_arenaAllocByte(mjData* d, size_t bytes, size_t alignment); |
| |
|
| | |
| | MJAPI void mj_initPlugin(const mjModel* m, mjData* d); |
| |
|
| | #ifndef ADDRESS_SANITIZER |
| |
|
| | |
| | MJAPI void mj_markStack(mjData* d); |
| |
|
| | |
| | MJAPI void mj_freeStack(mjData* d); |
| |
|
| | #else |
| |
|
| | void mj__markStack(mjData* d) __attribute__((noinline)); |
| | void mj__freeStack(mjData* d) __attribute__((noinline)); |
| |
|
| | #endif |
| |
|
| | |
| | MJAPI size_t mj_stackBytesAvailable(mjData* d); |
| |
|
| | |
| | MJAPI void* mj_stackAllocByte(mjData* d, size_t bytes, size_t alignment); |
| |
|
| | |
| | MJAPI void* mj_stackAllocInfo(mjData* d, size_t bytes, size_t alignment, |
| | const char* caller, int line); |
| |
|
| | |
| | #define mjSTACKALLOC(d, num, type) \ |
| | (type*) mj_stackAllocInfo(d, (num) * sizeof(type), _Alignof(type), __func__, __LINE__) |
| |
|
| | |
| | MJAPI mjtNum* mj_stackAllocNum(mjData* d, size_t size); |
| |
|
| | |
| | MJAPI int* mj_stackAllocInt(mjData* d, size_t size); |
| |
|
| | |
| | MJAPI void mj_deleteData(mjData* d); |
| |
|
| | |
| | static inline void mj_clearEfc(mjData* d) { |
| | #define X(type, name, nr, nc) d->name = NULL; |
| | MJDATA_ARENA_POINTERS |
| | #undef X |
| | d->nefc = 0; |
| | d->nisland = 0; |
| | d->contact = (mjContact*) d->arena; |
| | } |
| |
|
| | #ifdef __cplusplus |
| | } |
| | #endif |
| |
|
| | #endif |
| |
|