// Copyright 2024 DeepMind Technologies Limited // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. // You may obtain a copy of the License at // // http://www.apache.org/licenses/LICENSE-2.0 // // Unless required by applicable law or agreed to in writing, software // distributed under the License is distributed on an "AS IS" BASIS, // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. #ifndef MUJOCO_INCLUDE_MJSPEC_H_ #define MUJOCO_INCLUDE_MJSPEC_H_ #include #include #include // this is a C-API #ifdef __cplusplus #include #include #include extern "C" { #endif //-------------------------------- handles to strings and arrays ----------------------------------- #ifdef __cplusplus // C++: defined to be compatible with corresponding std types using mjString = std::string; using mjStringVec = std::vector; using mjIntVec = std::vector; using mjIntVecVec = std::vector>; using mjFloatVec = std::vector; using mjFloatVecVec = std::vector>; using mjDoubleVec = std::vector; using mjByteVec = std::vector; #else // C: opaque types typedef void mjString; typedef void mjStringVec; typedef void mjIntVec; typedef void mjIntVecVec; typedef void mjFloatVec; typedef void mjFloatVecVec; typedef void mjDoubleVec; typedef void mjByteVec; #endif //-------------------------------- enum types (mjt) ------------------------------------------------ typedef enum mjtGeomInertia_ { // type of inertia inference mjINERTIA_VOLUME = 0, // mass distributed in the volume mjINERTIA_SHELL, // mass distributed on the surface } mjtGeomInertia; typedef enum mjtMeshInertia_ { // type of mesh inertia mjINERTIA_CONVEX = 0, // convex mesh inertia mjINERTIA_EXACT, // exact mesh inertia mjINERTIA_LEGACY, // legacy mesh inertia } mjtMeshInertia; typedef enum mjtBuiltin_ { // type of built-in procedural texture mjBUILTIN_NONE = 0, // no built-in texture mjBUILTIN_GRADIENT, // gradient: rgb1->rgb2 mjBUILTIN_CHECKER, // checker pattern: rgb1, rgb2 mjBUILTIN_FLAT // 2d: rgb1; cube: rgb1-up, rgb2-side, rgb3-down } mjtBuiltin; typedef enum mjtMark_ { // mark type for procedural textures mjMARK_NONE = 0, // no mark mjMARK_EDGE, // edges mjMARK_CROSS, // cross mjMARK_RANDOM // random dots } mjtMark; typedef enum mjtLimited_ { // type of limit specification mjLIMITED_FALSE = 0, // not limited mjLIMITED_TRUE, // limited mjLIMITED_AUTO, // limited inferred from presence of range } mjtLimited; typedef enum mjtAlignFree_ { // whether to align free joints with the inertial frame mjALIGNFREE_FALSE = 0, // don't align mjALIGNFREE_TRUE, // align mjALIGNFREE_AUTO, // respect the global compiler flag } mjtAlignFree; typedef enum mjtInertiaFromGeom_ { // whether to infer body inertias from child geoms mjINERTIAFROMGEOM_FALSE = 0, // do not use; inertial element required mjINERTIAFROMGEOM_TRUE, // always use; overwrite inertial element mjINERTIAFROMGEOM_AUTO // use only if inertial element is missing } mjtInertiaFromGeom; typedef enum mjtOrientation_ { // type of orientation specifier mjORIENTATION_QUAT = 0, // quaternion mjORIENTATION_AXISANGLE, // axis and angle mjORIENTATION_XYAXES, // x and y axes mjORIENTATION_ZAXIS, // z axis (minimal rotation) mjORIENTATION_EULER, // Euler angles } mjtOrientation; //-------------------------------- attribute structs (mjs) ----------------------------------------- typedef struct mjsElement_ { // element type, do not modify mjtObj elemtype; // element type } mjsElement; typedef struct mjsCompiler_ { // compiler options mjtByte autolimits; // infer "limited" attribute based on range double boundmass; // enforce minimum body mass double boundinertia; // enforce minimum body diagonal inertia double settotalmass; // rescale masses and inertias; <=0: ignore mjtByte balanceinertia; // automatically impose A + B >= C rule mjtByte fitaabb; // meshfit to aabb instead of inertia box mjtByte degree; // angles in radians or degrees char eulerseq[3]; // sequence for euler rotations mjtByte discardvisual; // discard visual geoms in parser mjtByte usethread; // use multiple threads to speed up compiler mjtByte fusestatic; // fuse static bodies with parent int inertiafromgeom; // use geom inertias (mjtInertiaFromGeom) int inertiagrouprange[2]; // range of geom groups used to compute inertia int alignfree; // align free joints with inertial frame mjLROpt LRopt; // options for lengthrange computation } mjsCompiler; typedef struct mjSpec_ { // model specification mjsElement* element; // element type mjString* modelname; // model name // compiler data mjsCompiler compiler; // compiler options mjtByte strippath; // automatically strip paths from mesh files mjString* meshdir; // mesh and hfield directory mjString* texturedir; // texture directory // engine data mjOption option; // physics options mjVisual visual; // visual options mjStatistic stat; // statistics override (if defined) // sizes size_t memory; // number of bytes in arena+stack memory int nemax; // max number of equality constraints int nuserdata; // number of mjtNums in userdata int nuser_body; // number of mjtNums in body_user int nuser_jnt; // number of mjtNums in jnt_user int nuser_geom; // number of mjtNums in geom_user int nuser_site; // number of mjtNums in site_user int nuser_cam; // number of mjtNums in cam_user int nuser_tendon; // number of mjtNums in tendon_user int nuser_actuator; // number of mjtNums in actuator_user int nuser_sensor; // number of mjtNums in sensor_user int nkey; // number of keyframes int njmax; // (deprecated) max number of constraints int nconmax; // (deprecated) max number of detected contacts size_t nstack; // (deprecated) number of mjtNums in mjData stack // global data mjString* comment; // comment at top of XML mjString* modelfiledir; // path to model file // other mjtByte hasImplicitPluginElem; // already encountered an implicit plugin sensor/actuator } mjSpec; typedef struct mjsOrientation_ { // alternative orientation specifiers mjtOrientation type; // active orientation specifier double axisangle[4]; // axis and angle double xyaxes[6]; // x and y axes double zaxis[3]; // z axis (minimal rotation) double euler[3]; // Euler angles } mjsOrientation; typedef struct mjsPlugin_ { // plugin specification mjsElement* element; // element type mjString* name; // instance name mjString* plugin_name; // plugin name mjtByte active; // is the plugin active mjString* info; // message appended to compiler errors } mjsPlugin; typedef struct mjsBody_ { // body specification mjsElement* element; // element type mjString* name; // name mjString* childclass; // childclass name // body frame double pos[3]; // frame position double quat[4]; // frame orientation mjsOrientation alt; // frame alternative orientation // inertial frame double mass; // mass double ipos[3]; // inertial frame position double iquat[4]; // inertial frame orientation double inertia[3]; // diagonal inertia (in i-frame) mjsOrientation ialt; // inertial frame alternative orientation double fullinertia[6]; // non-axis-aligned inertia matrix // other mjtByte mocap; // is this a mocap body double gravcomp; // gravity compensation mjDoubleVec* userdata; // user data mjtByte explicitinertial; // whether to save the body with explicit inertial clause mjsPlugin plugin; // passive force plugin mjString* info; // message appended to compiler errors } mjsBody; typedef struct mjsFrame_ { // frame specification mjsElement* element; // element type mjString* name; // name mjString* childclass; // childclass name double pos[3]; // position double quat[4]; // orientation mjsOrientation alt; // alternative orientation mjString* info; // message appended to compiler errors } mjsFrame; typedef struct mjsJoint_ { // joint specification mjsElement* element; // element type mjString* name; // name mjtJoint type; // joint type // kinematics double pos[3]; // anchor position double axis[3]; // joint axis double ref; // value at reference configuration: qpos0 int align; // align free joint with body com (mjtAlignFree) // stiffness double stiffness; // stiffness coefficient double springref; // spring reference value: qpos_spring double springdamper[2]; // timeconst, dampratio // limits int limited; // does joint have limits (mjtLimited) double range[2]; // joint limits double margin; // margin value for joint limit detection mjtNum solref_limit[mjNREF]; // solver reference: joint limits mjtNum solimp_limit[mjNIMP]; // solver impedance: joint limits int actfrclimited; // are actuator forces on joint limited (mjtLimited) double actfrcrange[2]; // actuator force limits // dof properties double armature; // armature inertia (mass for slider) double damping; // damping coefficient double frictionloss; // friction loss mjtNum solref_friction[mjNREF]; // solver reference: dof friction mjtNum solimp_friction[mjNIMP]; // solver impedance: dof friction // other int group; // group mjtByte actgravcomp; // is gravcomp force applied via actuators mjDoubleVec* userdata; // user data mjString* info; // message appended to compiler errors } mjsJoint; typedef struct mjsGeom_ { // geom specification mjsElement* element; // element type mjString* name; // name mjtGeom type; // geom type // frame, size double pos[3]; // position double quat[4]; // orientation mjsOrientation alt; // alternative orientation double fromto[6]; // alternative for capsule, cylinder, box, ellipsoid double size[3]; // type-specific size // contact related int contype; // contact type int conaffinity; // contact affinity int condim; // contact dimensionality int priority; // contact priority double friction[3]; // one-sided friction coefficients: slide, roll, spin double solmix; // solver mixing for contact pairs mjtNum solref[mjNREF]; // solver reference mjtNum solimp[mjNIMP]; // solver impedance double margin; // margin for contact detection double gap; // include in solver if dist < margin-gap // inertia inference double mass; // used to compute density double density; // used to compute mass and inertia from volume or surface mjtGeomInertia typeinertia; // selects between surface and volume inertia // fluid forces mjtNum fluid_ellipsoid; // whether ellipsoid-fluid model is active mjtNum fluid_coefs[5]; // ellipsoid-fluid interaction coefs // visual mjString* material; // name of material float rgba[4]; // rgba when material is omitted int group; // group // other mjString* hfieldname; // heightfield attached to geom mjString* meshname; // mesh attached to geom double fitscale; // scale mesh uniformly mjDoubleVec* userdata; // user data mjsPlugin plugin; // sdf plugin mjString* info; // message appended to compiler errors } mjsGeom; typedef struct mjsSite_ { // site specification mjsElement* element; // element type mjString* name; // name // frame, size double pos[3]; // position double quat[4]; // orientation mjsOrientation alt; // alternative orientation double fromto[6]; // alternative for capsule, cylinder, box, ellipsoid double size[3]; // geom size // visual mjtGeom type; // geom type mjString* material; // name of material int group; // group float rgba[4]; // rgba when material is omitted // other mjDoubleVec* userdata; // user data mjString* info; // message appended to compiler errors } mjsSite; typedef struct mjsCamera_ { // camera specification mjsElement* element; // element type mjString* name; // name // extrinsics double pos[3]; // position double quat[4]; // orientation mjsOrientation alt; // alternative orientation mjtCamLight mode; // tracking mode mjString* targetbody; // target body for tracking/targeting // intrinsics int orthographic; // is camera orthographic double fovy; // y-field of view double ipd; // inter-pupilary distance float intrinsic[4]; // camera intrinsics (length) float sensor_size[2]; // sensor size (length) float resolution[2]; // resolution (pixel) float focal_length[2]; // focal length (length) float focal_pixel[2]; // focal length (pixel) float principal_length[2]; // principal point (length) float principal_pixel[2]; // principal point (pixel) // other mjDoubleVec* userdata; // user data mjString* info; // message appended to compiler errors } mjsCamera; typedef struct mjsLight_ { // light specification mjsElement* element; // element type mjString* name; // name // frame double pos[3]; // position double dir[3]; // direction mjtCamLight mode; // tracking mode mjString* targetbody; // target body for targeting // intrinsics mjtByte active; // is light active mjtByte directional; // is light directional or spot mjtByte castshadow; // does light cast shadows double bulbradius; // bulb radius, for soft shadows float attenuation[3]; // OpenGL attenuation (quadratic model) float cutoff; // OpenGL cutoff float exponent; // OpenGL exponent float ambient[3]; // ambient color float diffuse[3]; // diffuse color float specular[3]; // specular color // other mjString* info; // message appended to compiler errorsx } mjsLight; typedef struct mjsFlex_ { // flex specification mjsElement* element; // element type mjString* name; // name // contact properties int contype; // contact type int conaffinity; // contact affinity int condim; // contact dimensionality int priority; // contact priority double friction[3]; // one-sided friction coefficients: slide, roll, spin double solmix; // solver mixing for contact pairs mjtNum solref[mjNREF]; // solver reference mjtNum solimp[mjNIMP]; // solver impedance double margin; // margin for contact detection double gap; // include in solver if dist