| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| |
|
| | #ifndef MUJOCO_SRC_USER_USER_API_H_ |
| | #define MUJOCO_SRC_USER_USER_API_H_ |
| |
|
| | #include <math.h> |
| | #include <stddef.h> |
| | #include <mujoco/mjdata.h> |
| | #include <mujoco/mjexport.h> |
| | #include <mujoco/mjmodel.h> |
| | #include <mujoco/mjspec.h> |
| | #include <mujoco/mjtnum.h> |
| |
|
| |
|
| | |
| | #ifdef __cplusplus |
| | #include <string> |
| | #include <vector> |
| |
|
| | extern "C" { |
| | #endif |
| |
|
| | #define mjNAN NAN |
| |
|
| | |
| |
|
| | |
| | MJAPI mjSpec* mj_makeSpec(void); |
| |
|
| | |
| | MJAPI mjModel* mj_compile(mjSpec* s, const mjVFS* vfs); |
| |
|
| | |
| | MJAPI int mj_recompile(mjSpec* s, const mjVFS* vfs, mjModel* m, mjData* d); |
| |
|
| | |
| | MJAPI mjSpec* mj_copySpec(const mjSpec* s); |
| |
|
| | |
| | MJAPI const char* mjs_getError(mjSpec* s); |
| |
|
| | |
| | MJAPI int mjs_isWarning(mjSpec* s); |
| |
|
| | |
| | MJAPI void mj_deleteSpec(mjSpec* s); |
| |
|
| | |
| | MJAPI void mjs_addSpec(mjSpec* s, mjSpec* child); |
| |
|
| | |
| | MJAPI int mjs_activatePlugin(mjSpec* s, const char* name); |
| |
|
| | |
| | MJAPI int mjs_setDeepCopy(mjSpec* s, int deepcopy); |
| |
|
| | |
| | MJAPI int mj_copyBack(mjSpec* s, const mjModel* m); |
| |
|
| |
|
| | |
| |
|
| | |
| | MJAPI mjsElement* mjs_attach(mjsElement* parent, const mjsElement* child, |
| | const char* prefix, const char* suffix); |
| |
|
| |
|
| | |
| |
|
| | |
| | MJAPI mjsBody* mjs_addBody(mjsBody* body, const mjsDefault* def); |
| |
|
| | |
| | MJAPI mjsSite* mjs_addSite(mjsBody* body, const mjsDefault* def); |
| |
|
| | |
| | MJAPI mjsJoint* mjs_addJoint(mjsBody* body, const mjsDefault* def); |
| |
|
| | |
| | MJAPI mjsJoint* mjs_addFreeJoint(mjsBody* body); |
| |
|
| | |
| | MJAPI mjsGeom* mjs_addGeom(mjsBody* body, const mjsDefault* def); |
| |
|
| | |
| | MJAPI mjsCamera* mjs_addCamera(mjsBody* body, const mjsDefault* def); |
| |
|
| | |
| | MJAPI mjsLight* mjs_addLight(mjsBody* body, const mjsDefault* def); |
| |
|
| | |
| | MJAPI mjsFrame* mjs_addFrame(mjsBody* body, mjsFrame* parentframe); |
| |
|
| | |
| | MJAPI int mjs_delete(mjSpec* s, mjsElement* element); |
| |
|
| |
|
| | |
| |
|
| | |
| | MJAPI mjsActuator* mjs_addActuator(mjSpec* s, const mjsDefault* def); |
| |
|
| | |
| | MJAPI mjsSensor* mjs_addSensor(mjSpec* s); |
| |
|
| | |
| | MJAPI mjsFlex* mjs_addFlex(mjSpec* s); |
| |
|
| | |
| | MJAPI mjsPair* mjs_addPair(mjSpec* s, const mjsDefault* def); |
| |
|
| | |
| | MJAPI mjsExclude* mjs_addExclude(mjSpec* s); |
| |
|
| | |
| | MJAPI mjsEquality* mjs_addEquality(mjSpec* s, const mjsDefault* def); |
| |
|
| | |
| | MJAPI mjsTendon* mjs_addTendon(mjSpec* s, const mjsDefault* def); |
| |
|
| | |
| | MJAPI mjsWrap* mjs_wrapSite(mjsTendon* tendon, const char* name); |
| |
|
| | |
| | MJAPI mjsWrap* mjs_wrapGeom(mjsTendon* tendon, const char* name, const char* sidesite); |
| |
|
| | |
| | MJAPI mjsWrap* mjs_wrapJoint(mjsTendon* tendon, const char* name, double coef); |
| |
|
| | |
| | MJAPI mjsWrap* mjs_wrapPulley(mjsTendon* tendon, double divisor); |
| |
|
| | |
| | MJAPI mjsNumeric* mjs_addNumeric(mjSpec* s); |
| |
|
| | |
| | MJAPI mjsText* mjs_addText(mjSpec* s); |
| |
|
| | |
| | MJAPI mjsTuple* mjs_addTuple(mjSpec* s); |
| |
|
| | |
| | MJAPI mjsKey* mjs_addKey(mjSpec* s); |
| |
|
| | |
| | MJAPI mjsPlugin* mjs_addPlugin(mjSpec* s); |
| |
|
| | |
| | MJAPI mjsDefault* mjs_addDefault(mjSpec* s, const char* classname, const mjsDefault* parent); |
| |
|
| |
|
| | |
| |
|
| | |
| | MJAPI const char* mjs_setToMotor(mjsActuator* actuator); |
| |
|
| | |
| | MJAPI const char* mjs_setToPosition(mjsActuator* actuator, double kp, double kv[1], |
| | double dampratio[1], double timeconst[1], double inheritrange); |
| |
|
| | |
| | MJAPI const char* mjs_setToIntVelocity(mjsActuator* actuator, double kp, double kv[1], |
| | double dampratio[1], double timeconst[1], double inheritrange); |
| |
|
| | |
| | MJAPI const char* mjs_setToVelocity(mjsActuator* actuator, double kv); |
| |
|
| | |
| | MJAPI const char* mjs_setToDamper(mjsActuator* actuator, double kv); |
| |
|
| | |
| | MJAPI const char* mjs_setToCylinder(mjsActuator* actuator, double timeconst, |
| | double bias, double area, double diameter); |
| |
|
| | |
| | MJAPI const char* mjs_setToMuscle(mjsActuator* actuator, double timeconst[2], double tausmooth, |
| | double range[2], double force, double scale, double lmin, |
| | double lmax, double vmax, double fpmax, double fvmax); |
| |
|
| | |
| | MJAPI const char* mjs_setToAdhesion(mjsActuator* actuator, double gain); |
| |
|
| | |
| |
|
| | |
| | MJAPI mjsMesh* mjs_addMesh(mjSpec* s, const mjsDefault* def); |
| |
|
| | |
| | MJAPI mjsHField* mjs_addHField(mjSpec* s); |
| |
|
| | |
| | MJAPI mjsSkin* mjs_addSkin(mjSpec* s); |
| |
|
| | |
| | MJAPI mjsTexture* mjs_addTexture(mjSpec* s); |
| |
|
| | |
| | MJAPI mjsMaterial* mjs_addMaterial(mjSpec* s, const mjsDefault* def); |
| |
|
| |
|
| | |
| |
|
| | |
| | MJAPI mjSpec* mjs_getSpec(mjsElement* element); |
| |
|
| | |
| | MJAPI mjSpec* mjs_findSpec(mjSpec* spec, const char* name); |
| |
|
| | |
| | MJAPI mjsBody* mjs_findBody(mjSpec* s, const char* name); |
| |
|
| | |
| | MJAPI mjsElement* mjs_findElement(mjSpec* s, mjtObj type, const char* name); |
| |
|
| | |
| | MJAPI mjsBody* mjs_findChild(mjsBody* body, const char* name); |
| |
|
| | |
| | MJAPI mjsBody* mjs_getParent(mjsElement* element); |
| |
|
| | |
| | MJAPI mjsFrame* mjs_getFrame(mjsElement* element); |
| |
|
| | |
| | MJAPI mjsFrame* mjs_findFrame(mjSpec* s, const char* name); |
| |
|
| | |
| | MJAPI mjsDefault* mjs_getDefault(mjsElement* element); |
| |
|
| | |
| | MJAPI mjsDefault* mjs_findDefault(mjSpec* s, const char* classname); |
| |
|
| | |
| | MJAPI mjsDefault* mjs_getSpecDefault(mjSpec* s); |
| |
|
| | |
| | MJAPI int mjs_getId(mjsElement* element); |
| |
|
| |
|
| | |
| |
|
| | |
| | MJAPI mjsElement* mjs_firstChild(mjsBody* body, mjtObj type, int recurse); |
| |
|
| | |
| | |
| | MJAPI mjsElement* mjs_nextChild(mjsBody* body, mjsElement* child, int recurse); |
| |
|
| | |
| | MJAPI mjsElement* mjs_firstElement(mjSpec* s, mjtObj type); |
| |
|
| | |
| | MJAPI mjsElement* mjs_nextElement(mjSpec* s, mjsElement* element); |
| |
|
| | |
| | MJAPI mjsBody* mjs_asBody(mjsElement* element); |
| |
|
| | |
| | MJAPI mjsGeom* mjs_asGeom(mjsElement* element); |
| |
|
| | |
| | MJAPI mjsJoint* mjs_asJoint(mjsElement* element); |
| |
|
| | |
| | MJAPI mjsSite* mjs_asSite(mjsElement* element); |
| |
|
| | |
| | MJAPI mjsCamera* mjs_asCamera(mjsElement* element); |
| |
|
| | |
| | MJAPI mjsLight* mjs_asLight(mjsElement* element); |
| |
|
| | |
| | MJAPI mjsFrame* mjs_asFrame(mjsElement* element); |
| |
|
| | |
| | MJAPI mjsActuator* mjs_asActuator(mjsElement* element); |
| |
|
| | |
| | MJAPI mjsSensor* mjs_asSensor(mjsElement* element); |
| |
|
| | |
| | MJAPI mjsFlex* mjs_asFlex(mjsElement* element); |
| |
|
| | |
| | MJAPI mjsPair* mjs_asPair(mjsElement* element); |
| |
|
| | |
| | MJAPI mjsEquality* mjs_asEquality(mjsElement* element); |
| |
|
| | |
| | MJAPI mjsExclude* mjs_asExclude(mjsElement* element); |
| |
|
| | |
| | MJAPI mjsTendon* mjs_asTendon(mjsElement* element); |
| |
|
| | |
| | MJAPI mjsNumeric* mjs_asNumeric(mjsElement* element); |
| |
|
| | |
| | MJAPI mjsText* mjs_asText(mjsElement* element); |
| |
|
| | |
| | MJAPI mjsTuple* mjs_asTuple(mjsElement* element); |
| |
|
| | |
| | MJAPI mjsKey* mjs_asKey(mjsElement* element); |
| |
|
| | |
| | MJAPI mjsMesh* mjs_asMesh(mjsElement* element); |
| |
|
| | |
| | MJAPI mjsHField* mjs_asHField(mjsElement* element); |
| |
|
| | |
| | MJAPI mjsSkin* mjs_asSkin(mjsElement* element); |
| |
|
| | |
| | MJAPI mjsTexture* mjs_asTexture(mjsElement* element); |
| |
|
| | |
| | MJAPI mjsMaterial* mjs_asMaterial(mjsElement* element); |
| |
|
| | |
| | MJAPI mjsPlugin* mjs_asPlugin(mjsElement* element); |
| |
|
| |
|
| | |
| |
|
| | |
| | MJAPI int mjs_setName(mjsElement* element, const char* name); |
| |
|
| | |
| | MJAPI void mjs_setBuffer(mjByteVec* dest, const void* array, int size); |
| |
|
| | |
| | MJAPI void mjs_setString(mjString* dest, const char* text); |
| |
|
| | |
| | MJAPI void mjs_setStringVec(mjStringVec* dest, const char* text); |
| |
|
| | |
| | MJAPI mjtByte mjs_setInStringVec(mjStringVec* dest, int i, const char* text); |
| |
|
| | |
| | MJAPI void mjs_appendString(mjStringVec* dest, const char* text); |
| |
|
| | |
| | MJAPI void mjs_setInt(mjIntVec* dest, const int* array, int size); |
| |
|
| | |
| | MJAPI void mjs_appendIntVec(mjIntVecVec* dest, const int* array, int size); |
| |
|
| | |
| | MJAPI void mjs_setFloat(mjFloatVec* dest, const float* array, int size); |
| |
|
| | |
| | MJAPI void mjs_appendFloatVec(mjFloatVecVec* dest, const float* array, int size); |
| |
|
| | |
| | MJAPI void mjs_setDouble(mjDoubleVec* dest, const double* array, int size); |
| |
|
| | |
| | MJAPI void mjs_setPluginAttributes(mjsPlugin* plugin, void* attributes); |
| |
|
| |
|
| | |
| |
|
| | |
| | MJAPI mjString* mjs_getName(mjsElement* element); |
| |
|
| | |
| | MJAPI const char* mjs_getString(const mjString* source); |
| |
|
| | |
| | MJAPI const double* mjs_getDouble(const mjDoubleVec* source, int* size); |
| |
|
| | |
| | MJAPI const void* mjs_getPluginAttributes(const mjsPlugin* plugin); |
| |
|
| |
|
| | |
| |
|
| | |
| | MJAPI void mjs_setDefault(mjsElement* element, const mjsDefault* def); |
| |
|
| | |
| | MJAPI int mjs_setFrame(mjsElement* dest, mjsFrame* frame); |
| |
|
| | |
| | MJAPI const char* mjs_resolveOrientation(double quat[4], mjtByte degree, const char* sequence, |
| | const mjsOrientation* orientation); |
| |
|
| | |
| | MJAPI mjsFrame* mjs_bodyToFrame(mjsBody** body); |
| |
|
| | |
| | MJAPI void mjs_setUserValue(mjsElement* element, const char* key, const void* data); |
| |
|
| | |
| | MJAPI void mjs_setUserValueWithCleanup(mjsElement* element, const char* key, |
| | const void* data, |
| | void (*cleanup)(const void*)); |
| |
|
| | |
| | MJAPI const void* mjs_getUserValue(mjsElement* element, const char* key); |
| |
|
| | |
| | MJAPI void mjs_deleteUserValue(mjsElement* element, const char* key); |
| |
|
| |
|
| | |
| |
|
| | |
| | MJAPI void mjs_defaultSpec(mjSpec* spec); |
| |
|
| | |
| | MJAPI void mjs_defaultOrientation(mjsOrientation* orient); |
| |
|
| | |
| | MJAPI void mjs_defaultBody(mjsBody* body); |
| |
|
| | |
| | MJAPI void mjs_defaultFrame(mjsFrame* frame); |
| |
|
| | |
| | MJAPI void mjs_defaultJoint(mjsJoint* joint); |
| |
|
| | |
| | MJAPI void mjs_defaultGeom(mjsGeom* geom); |
| |
|
| | |
| | MJAPI void mjs_defaultSite(mjsSite* site); |
| |
|
| | |
| | MJAPI void mjs_defaultCamera(mjsCamera* camera); |
| |
|
| | |
| | MJAPI void mjs_defaultLight(mjsLight* light); |
| |
|
| | |
| | MJAPI void mjs_defaultFlex(mjsFlex* flex); |
| |
|
| | |
| | MJAPI void mjs_defaultMesh(mjsMesh* mesh); |
| |
|
| | |
| | MJAPI void mjs_defaultHField(mjsHField* hfield); |
| |
|
| | |
| | MJAPI void mjs_defaultSkin(mjsSkin* skin); |
| |
|
| | |
| | MJAPI void mjs_defaultTexture(mjsTexture* texture); |
| |
|
| | |
| | MJAPI void mjs_defaultMaterial(mjsMaterial* material); |
| |
|
| | |
| | MJAPI void mjs_defaultPair(mjsPair* pair); |
| |
|
| | |
| | MJAPI void mjs_defaultEquality(mjsEquality* equality); |
| |
|
| | |
| | MJAPI void mjs_defaultTendon(mjsTendon* tendon); |
| |
|
| | |
| | MJAPI void mjs_defaultActuator(mjsActuator* actuator); |
| |
|
| | |
| | MJAPI void mjs_defaultSensor(mjsSensor* sensor); |
| |
|
| | |
| | MJAPI void mjs_defaultNumeric(mjsNumeric* numeric); |
| |
|
| | |
| | MJAPI void mjs_defaultText(mjsText* text); |
| |
|
| | |
| | MJAPI void mjs_defaultTuple(mjsTuple* tuple); |
| |
|
| | |
| | MJAPI void mjs_defaultKey(mjsKey* key); |
| |
|
| | |
| | MJAPI void mjs_defaultPlugin(mjsPlugin* plugin); |
| |
|
| |
|
| | |
| |
|
| | typedef struct mjCache_* mjCache; |
| |
|
| | |
| | MJAPI void mj_setCacheSize(mjCache cache, size_t size); |
| |
|
| | |
| | MJAPI mjCache mj_globalCache(void); |
| |
|
| | #ifdef __cplusplus |
| | } |
| | #endif |
| |
|
| | #endif |
| |
|