// Type definitions for Emscripten 1.39.16 // Project: https://emscripten.org // Definitions by: Kensuke Matsuzaki // Periklis Tsirakidis // Bumsik Kim // Louis DeScioli // Definitions: https://github.com/DefinitelyTyped/DefinitelyTyped/blob/master/types/emscripten/index.d.ts // TypeScript Version: 2.2 declare module "mujoco-wasm"; /** Other WebAssembly declarations, for compatibility with older versions of Typescript */ declare namespace WebAssembly { interface Module {} } declare namespace Emscripten { interface FileSystemType {} type EnvironmentType = 'WEB' | 'NODE' | 'SHELL' | 'WORKER'; type JSType = 'number' | 'string' | 'array' | 'boolean'; type TypeCompatibleWithC = number | string | any[] | boolean; type CIntType = 'i8' | 'i16' | 'i32' | 'i64'; type CFloatType = 'float' | 'double'; type CPointerType = 'i8*' | 'i16*' | 'i32*' | 'i64*' | 'float*' | 'double*' | '*'; type CType = CIntType | CFloatType | CPointerType; type WebAssemblyImports = Array<{ name: string; kind: string; }>; type WebAssemblyExports = Array<{ module: string; name: string; kind: string; }>; interface CCallOpts { async?: boolean | undefined; } } interface EmscriptenModule { print(str: string): void; printErr(str: string): void; arguments: string[]; environment: Emscripten.EnvironmentType; preInit: Array<{ (): void }>; preRun: Array<{ (): void }>; postRun: Array<{ (): void }>; onAbort: { (what: any): void }; onRuntimeInitialized: { (): void }; preinitializedWebGLContext: WebGLRenderingContext; noInitialRun: boolean; noExitRuntime: boolean; logReadFiles: boolean; filePackagePrefixURL: string; wasmBinary: ArrayBuffer; destroy(object: object): void; getPreloadedPackage(remotePackageName: string, remotePackageSize: number): ArrayBuffer; instantiateWasm( imports: Emscripten.WebAssemblyImports, successCallback: (module: WebAssembly.Module) => void, ): Emscripten.WebAssemblyExports; locateFile(url: string, scriptDirectory: string): string; onCustomMessage(event: MessageEvent): void; // USE_TYPED_ARRAYS == 1 HEAP: Int32Array; IHEAP: Int32Array; FHEAP: Float64Array; // USE_TYPED_ARRAYS == 2 HEAP8: Int8Array; HEAP16: Int16Array; HEAP32: Int32Array; HEAPU8: Uint8Array; HEAPU16: Uint16Array; HEAPU32: Uint32Array; HEAPF32: Float32Array; HEAPF64: Float64Array; TOTAL_STACK: number; TOTAL_MEMORY: number; FAST_MEMORY: number; addOnPreRun(cb: () => any): void; addOnInit(cb: () => any): void; addOnPreMain(cb: () => any): void; addOnExit(cb: () => any): void; addOnPostRun(cb: () => any): void; preloadedImages: any; preloadedAudios: any; _malloc(size: number): number; _free(ptr: number): void; } /** * A factory function is generated when setting the `MODULARIZE` build option * to `1` in your Emscripten build. It return a Promise that resolves to an * initialized, ready-to-call `EmscriptenModule` instance. * * By default, the factory function will be named `Module`. It's recommended to * use the `EXPORT_ES6` option, in which the factory function will be the * default export. If used without `EXPORT_ES6`, the factory function will be a * global variable. You can rename the variable using the `EXPORT_NAME` build * option. It's left to you to declare any global variables as needed in your * application's types. * @param moduleOverrides Default properties for the initialized module. */ type EmscriptenModuleFactory = ( moduleOverrides?: Partial, ) => Promise; declare namespace FS { interface Lookup { path: string; node: FSNode; } interface FSStream {} interface FSNode {} interface ErrnoError {} let ignorePermissions: boolean; let trackingDelegate: any; let tracking: any; let genericErrors: any; // // paths // function lookupPath(path: string, opts: any): Lookup; function getPath(node: FSNode): string; // // nodes // function isFile(mode: number): boolean; function isDir(mode: number): boolean; function isLink(mode: number): boolean; function isChrdev(mode: number): boolean; function isBlkdev(mode: number): boolean; function isFIFO(mode: number): boolean; function isSocket(mode: number): boolean; // // devices // function major(dev: number): number; function minor(dev: number): number; function makedev(ma: number, mi: number): number; function registerDevice(dev: number, ops: any): void; // // core // function syncfs(populate: boolean, callback: (e: any) => any): void; function syncfs(callback: (e: any) => any, populate?: boolean): void; function mount(type: Emscripten.FileSystemType, opts: any, mountpoint: string): any; function unmount(mountpoint: string): void; function mkdir(path: string, mode?: number): any; function mkdev(path: string, mode?: number, dev?: number): any; function symlink(oldpath: string, newpath: string): any; function rename(old_path: string, new_path: string): void; function rmdir(path: string): void; function readdir(path: string): any; function unlink(path: string): void; function readlink(path: string): string; function stat(path: string, dontFollow?: boolean): any; function lstat(path: string): any; function chmod(path: string, mode: number, dontFollow?: boolean): void; function lchmod(path: string, mode: number): void; function fchmod(fd: number, mode: number): void; function chown(path: string, uid: number, gid: number, dontFollow?: boolean): void; function lchown(path: string, uid: number, gid: number): void; function fchown(fd: number, uid: number, gid: number): void; function truncate(path: string, len: number): void; function ftruncate(fd: number, len: number): void; function utime(path: string, atime: number, mtime: number): void; function open(path: string, flags: string, mode?: number, fd_start?: number, fd_end?: number): FSStream; function close(stream: FSStream): void; function llseek(stream: FSStream, offset: number, whence: number): any; function read(stream: FSStream, buffer: ArrayBufferView, offset: number, length: number, position?: number): number; function write( stream: FSStream, buffer: ArrayBufferView, offset: number, length: number, position?: number, canOwn?: boolean, ): number; function allocate(stream: FSStream, offset: number, length: number): void; function mmap( stream: FSStream, buffer: ArrayBufferView, offset: number, length: number, position: number, prot: number, flags: number, ): any; function ioctl(stream: FSStream, cmd: any, arg: any): any; function readFile(path: string, opts: { encoding: 'binary'; flags?: string | undefined }): Uint8Array; function readFile(path: string, opts: { encoding: 'utf8'; flags?: string | undefined }): string; function readFile(path: string, opts?: { flags?: string | undefined }): Uint8Array; function writeFile(path: string, data: string | ArrayBufferView, opts?: { flags?: string | undefined }): void; // Ge added this manually form the FS namespace. function unlink(path: Path): void; function mkdir(path: Path, mode?: Mode): void; function rmdir(path: Path): void; function readdir(path: Path): string[]; function stat(path: Path): any; function rename(oldPath: Path, newPath: Path): void; function readlink(path: Path): Path; function symlink(oldPath: Path, newPath: Path): void; function chmod(path: Path, mode: Mode): void; function lstat(path: Path): any; function mknod(path: Path, mode: Mode, dev: any): void; function mount(type: any, opts: any, mountpoint: Path): void; function umount(mountpoint: Path): void; function open(path: Path, flags: Flags, mode?: Mode): number; function close(fd: number): void; function llseek(fd: number, offset: number, whence: number): number; function read(fd: number, buffer: Uint8Array, offset: number, length: number, position: number): number; function write(fd: number, buffer: Uint8Array, offset: number, length: number, position: number): number; function ioctl(fd: number, request: number, varargs: any): number; function isDir(mode: Mode): boolean; function isFile(mode: Mode): boolean; function isLink(mode: Mode): boolean; function major(dev: number): number; function minor(dev: number): number; function makedev(major: number, minor: number): number; function registerDevice(dev: number, ops: any): void; function forceLoadFile(path: Path): void; function analyzePath(path: Path, dontResolveLastLink?: boolean): any; function loadFilesFromDB(paths: Path[], onload: () => void, onerror: (error: any) => void): void; // // module-level FS code // function cwd(): string; function chdir(path: string): void; function init( input: null | (() => number | null), output: null | ((c: number) => any), error: null | ((c: number) => any), ): void; function createLazyFile( parent: string | FSNode, name: string, url: string, canRead: boolean, canWrite: boolean, ): FSNode; function createPreloadedFile( parent: string | FSNode, name: string, url: string, canRead: boolean, canWrite: boolean, onload?: () => void, onerror?: () => void, dontCreateFile?: boolean, canOwn?: boolean, ): void; function createDataFile( parent: string | FSNode, name: string, data: ArrayBufferView, canRead: boolean, canWrite: boolean, canOwn: boolean, ): FSNode; } declare var MEMFS: Emscripten.FileSystemType; declare var NODEFS: Emscripten.FileSystemType; declare var IDBFS: Emscripten.FileSystemType; // https://emscripten.org/docs/porting/connecting_cpp_and_javascript/Interacting-with-code.html type StringToType = R extends Emscripten.JSType ? { number: number; string: string; array: number[] | string[] | boolean[] | Uint8Array | Int8Array; boolean: boolean; null: null; }[R] : never; type ArgsToType> = Extract< { [P in keyof T]: StringToType; }, any[] >; type ReturnToType = R extends null ? null : StringToType>; // ENUMS /** disable default feature bitflags */ export enum mjtDisableBit { /** entire constraint solver */ mjDSBL_CONSTRAINT , /** equality constraints */ mjDSBL_EQUALITY , /** joint and tendon frictionloss constraints */ mjDSBL_FRICTIONLOSS , /** joint and tendon limit constraints */ mjDSBL_LIMIT , /** contact constraints */ mjDSBL_CONTACT , /** passive spring forces */ mjDSBL_SPRING , /** passive damping forces */ mjDSBL_DAMPER , /** gravitational forces */ mjDSBL_GRAVITY , /** clamp control to specified range */ mjDSBL_CLAMPCTRL , /** warmstart constraint solver */ mjDSBL_WARMSTART , /** remove collisions with parent body */ mjDSBL_FILTERPARENT , /** apply actuation forces */ mjDSBL_ACTUATION , /** integrator safety: make ref[0]>=2*timestep */ mjDSBL_REFSAFE , /** sensors */ mjDSBL_SENSOR , /** mid-phase collision filtering */ mjDSBL_MIDPHASE , /** implicit integration of joint damping in Euler integrator */ mjDSBL_EULERDAMP , /** automatic reset when numerical issues are detected */ mjDSBL_AUTORESET , /** native convex collision detection */ mjDSBL_NATIVECCD , /** constraint island discovery */ mjDSBL_ISLAND , /** number of disable flags */ mjNDISABLE , } /** enable optional feature bitflags */ export enum mjtEnableBit { /** override contact parameters */ mjENBL_OVERRIDE , /** energy computation */ mjENBL_ENERGY , /** record solver statistics */ mjENBL_FWDINV , /** discrete-time inverse dynamics */ mjENBL_INVDISCRETE , /** multi-point convex collision detection */ mjENBL_MULTICCD , /** number of enable flags */ mjNENABLE , } /** type of degree of freedom */ export enum mjtJoint { /** global position and orientation (quat) (7) */ mjJNT_FREE , /** orientation (quat) relative to parent (4) */ mjJNT_BALL , /** sliding distance along body-fixed axis (1) */ mjJNT_SLIDE , /** rotation angle (rad) around body-fixed axis (1) */ mjJNT_HINGE , } /** type of geometric shape */ export enum mjtGeom { /** plane */ mjGEOM_PLANE , /** height field */ mjGEOM_HFIELD , /** sphere */ mjGEOM_SPHERE , /** capsule */ mjGEOM_CAPSULE , /** ellipsoid */ mjGEOM_ELLIPSOID , /** cylinder */ mjGEOM_CYLINDER , /** box */ mjGEOM_BOX , /** mesh */ mjGEOM_MESH , /** signed distance field */ mjGEOM_SDF , /** number of regular geom types */ mjNGEOMTYPES , /** arrow */ mjGEOM_ARROW , /** arrow without wedges */ mjGEOM_ARROW1 , /** arrow in both directions */ mjGEOM_ARROW2 , /** line */ mjGEOM_LINE , /** box with line edges */ mjGEOM_LINEBOX , /** flex */ mjGEOM_FLEX , /** skin */ mjGEOM_SKIN , /** text label */ mjGEOM_LABEL , /** triangle */ mjGEOM_TRIANGLE , /** missing geom type */ mjGEOM_NONE , } /** tracking mode for camera and light */ export enum mjtCamLight { /** pos and rot fixed in body */ mjCAMLIGHT_FIXED , /** pos tracks body, rot fixed in global */ mjCAMLIGHT_TRACK , /** pos tracks subtree com, rot fixed in body */ mjCAMLIGHT_TRACKCOM , /** pos fixed in body, rot tracks target body */ mjCAMLIGHT_TARGETBODY , /** pos fixed in body, rot tracks target subtree com */ mjCAMLIGHT_TARGETBODYCOM , } /** type of light */ export enum mjtLightType { /** spot */ mjLIGHT_SPOT , /** directional */ mjLIGHT_DIRECTIONAL , /** point */ mjLIGHT_POINT , /** image-based */ mjLIGHT_IMAGE , } /** type of texture */ export enum mjtTexture { /** 2d texture, suitable for planes and hfields */ mjTEXTURE_2D , /** cube texture, suitable for all other geom types */ mjTEXTURE_CUBE , /** cube texture used as skybox */ mjTEXTURE_SKYBOX , } /** role of texture map in rendering */ export enum mjtTextureRole { /** unspecified */ mjTEXROLE_USER , /** base color (albedo) */ mjTEXROLE_RGB , /** ambient occlusion */ mjTEXROLE_OCCLUSION , /** roughness */ mjTEXROLE_ROUGHNESS , /** metallic */ mjTEXROLE_METALLIC , /** normal (bump) map */ mjTEXROLE_NORMAL , /** transperancy */ mjTEXROLE_OPACITY , /** light emission */ mjTEXROLE_EMISSIVE , /** base color, opacity */ mjTEXROLE_RGBA , /** occlusion, roughness, metallic */ mjTEXROLE_ORM , /** */ mjNTEXROLE , } /** type of color space encoding */ export enum mjtColorSpace { /** attempts to autodetect color space, defaults to linear */ mjCOLORSPACE_AUTO , /** linear color space */ mjCOLORSPACE_LINEAR , /** standard RGB color space */ mjCOLORSPACE_SRGB , } /** integrator mode */ export enum mjtIntegrator { /** semi-implicit Euler */ mjINT_EULER , /** 4th-order Runge Kutta */ mjINT_RK4 , /** implicit in velocity */ mjINT_IMPLICIT , /** implicit in velocity, no rne derivative */ mjINT_IMPLICITFAST , } /** type of friction cone */ export enum mjtCone { /** pyramidal */ mjCONE_PYRAMIDAL , /** elliptic */ mjCONE_ELLIPTIC , } /** type of constraint Jacobian */ export enum mjtJacobian { /** dense */ mjJAC_DENSE , /** sparse */ mjJAC_SPARSE , /** dense if nv<60, sparse otherwise */ mjJAC_AUTO , } /** constraint solver algorithm */ export enum mjtSolver { /** PGS (dual) */ mjSOL_PGS , /** CG (primal) */ mjSOL_CG , /** Newton (primal) */ mjSOL_NEWTON , } /** type of equality constraint */ export enum mjtEq { /** connect two bodies at a point (ball joint) */ mjEQ_CONNECT , /** fix relative position and orientation of two bodies */ mjEQ_WELD , /** couple the values of two scalar joints with cubic */ mjEQ_JOINT , /** couple the lengths of two tendons with cubic */ mjEQ_TENDON , /** fix all edge lengths of a flex */ mjEQ_FLEX , /** unsupported, will cause an error if used */ mjEQ_DISTANCE , } /** type of tendon wrap object */ export enum mjtWrap { /** null object */ mjWRAP_NONE , /** constant moment arm */ mjWRAP_JOINT , /** pulley used to split tendon */ mjWRAP_PULLEY , /** pass through site */ mjWRAP_SITE , /** wrap around sphere */ mjWRAP_SPHERE , /** wrap around (infinite) cylinder */ mjWRAP_CYLINDER , } /** type of actuator transmission */ export enum mjtTrn { /** force on joint */ mjTRN_JOINT , /** force on joint, expressed in parent frame */ mjTRN_JOINTINPARENT , /** force via slider-crank linkage */ mjTRN_SLIDERCRANK , /** force on tendon */ mjTRN_TENDON , /** force on site */ mjTRN_SITE , /** adhesion force on a body's geoms */ mjTRN_BODY , /** undefined transmission type */ mjTRN_UNDEFINED , } /** type of actuator dynamics */ export enum mjtDyn { /** no internal dynamics; ctrl specifies force */ mjDYN_NONE , /** integrator: da/dt = u */ mjDYN_INTEGRATOR , /** linear filter: da/dt = (u-a) / tau */ mjDYN_FILTER , /** linear filter: da/dt = (u-a) / tau, with exact integration */ mjDYN_FILTEREXACT , /** piece-wise linear filter with two time constants */ mjDYN_MUSCLE , /** user-defined dynamics type */ mjDYN_USER , } /** type of actuator gain */ export enum mjtGain { /** fixed gain */ mjGAIN_FIXED , /** const + kp*length + kv*velocity */ mjGAIN_AFFINE , /** muscle FLV curve computed by mju_muscleGain() */ mjGAIN_MUSCLE , /** user-defined gain type */ mjGAIN_USER , } /** type of actuator bias */ export enum mjtBias { /** no bias */ mjBIAS_NONE , /** const + kp*length + kv*velocity */ mjBIAS_AFFINE , /** muscle passive force computed by mju_muscleBias() */ mjBIAS_MUSCLE , /** user-defined bias type */ mjBIAS_USER , } /** type of MujoCo object */ export enum mjtObj { /** unknown object type */ mjOBJ_UNKNOWN , /** body */ mjOBJ_BODY , /** body, used to access regular frame instead of i-frame */ mjOBJ_XBODY , /** joint */ mjOBJ_JOINT , /** dof */ mjOBJ_DOF , /** geom */ mjOBJ_GEOM , /** site */ mjOBJ_SITE , /** camera */ mjOBJ_CAMERA , /** light */ mjOBJ_LIGHT , /** flex */ mjOBJ_FLEX , /** mesh */ mjOBJ_MESH , /** skin */ mjOBJ_SKIN , /** heightfield */ mjOBJ_HFIELD , /** texture */ mjOBJ_TEXTURE , /** material for rendering */ mjOBJ_MATERIAL , /** geom pair to include */ mjOBJ_PAIR , /** body pair to exclude */ mjOBJ_EXCLUDE , /** equality constraint */ mjOBJ_EQUALITY , /** tendon */ mjOBJ_TENDON , /** actuator */ mjOBJ_ACTUATOR , /** sensor */ mjOBJ_SENSOR , /** numeric */ mjOBJ_NUMERIC , /** text */ mjOBJ_TEXT , /** tuple */ mjOBJ_TUPLE , /** keyframe */ mjOBJ_KEY , /** plugin instance */ mjOBJ_PLUGIN , /** number of object types */ mjNOBJECT , /** frame */ mjOBJ_FRAME , /** default */ mjOBJ_DEFAULT , /** entire model */ mjOBJ_MODEL , } /** type of sensor */ export enum mjtSensor { /** scalar contact normal forces summed over sensor zone */ mjSENS_TOUCH , /** 3D linear acceleration, in local frame */ mjSENS_ACCELEROMETER , /** 3D linear velocity, in local frame */ mjSENS_VELOCIMETER , /** 3D angular velocity, in local frame */ mjSENS_GYRO , /** 3D force between site's body and its parent body */ mjSENS_FORCE , /** 3D torque between site's body and its parent body */ mjSENS_TORQUE , /** 3D magnetometer */ mjSENS_MAGNETOMETER , /** scalar distance to nearest geom or site along z-axis */ mjSENS_RANGEFINDER , /** pixel coordinates of a site in the camera image */ mjSENS_CAMPROJECTION , /** scalar joint position (hinge and slide only) */ mjSENS_JOINTPOS , /** scalar joint velocity (hinge and slide only) */ mjSENS_JOINTVEL , /** scalar tendon position */ mjSENS_TENDONPOS , /** scalar tendon velocity */ mjSENS_TENDONVEL , /** scalar actuator position */ mjSENS_ACTUATORPOS , /** scalar actuator velocity */ mjSENS_ACTUATORVEL , /** scalar actuator force */ mjSENS_ACTUATORFRC , /** scalar actuator force, measured at the joint */ mjSENS_JOINTACTFRC , /** scalar actuator force, measured at the tendon */ mjSENS_TENDONACTFRC , /** 4D ball joint quaternion */ mjSENS_BALLQUAT , /** 3D ball joint angular velocity */ mjSENS_BALLANGVEL , /** joint limit distance-margin */ mjSENS_JOINTLIMITPOS , /** joint limit velocity */ mjSENS_JOINTLIMITVEL , /** joint limit force */ mjSENS_JOINTLIMITFRC , /** tendon limit distance-margin */ mjSENS_TENDONLIMITPOS , /** tendon limit velocity */ mjSENS_TENDONLIMITVEL , /** tendon limit force */ mjSENS_TENDONLIMITFRC , /** 3D position */ mjSENS_FRAMEPOS , /** 4D unit quaternion orientation */ mjSENS_FRAMEQUAT , /** 3D unit vector: x-axis of object's frame */ mjSENS_FRAMEXAXIS , /** 3D unit vector: y-axis of object's frame */ mjSENS_FRAMEYAXIS , /** 3D unit vector: z-axis of object's frame */ mjSENS_FRAMEZAXIS , /** 3D linear velocity */ mjSENS_FRAMELINVEL , /** 3D angular velocity */ mjSENS_FRAMEANGVEL , /** 3D linear acceleration */ mjSENS_FRAMELINACC , /** 3D angular acceleration */ mjSENS_FRAMEANGACC , /** 3D center of mass of subtree */ mjSENS_SUBTREECOM , /** 3D linear velocity of subtree */ mjSENS_SUBTREELINVEL , /** 3D angular momentum of subtree */ mjSENS_SUBTREEANGMOM , /** 1 if object is inside a site, 0 otherwise */ mjSENS_INSIDESITE , /** signed distance between two geoms */ mjSENS_GEOMDIST , /** normal direction between two geoms */ mjSENS_GEOMNORMAL , /** segment between two geoms */ mjSENS_GEOMFROMTO , /** contacts which occurred during the simulation */ mjSENS_CONTACT , /** potential energy */ mjSENS_E_POTENTIAL , /** kinetic energy */ mjSENS_E_KINETIC , /** simulation time */ mjSENS_CLOCK , /** tactile sensor */ mjSENS_TACTILE , /** plugin-controlled */ mjSENS_PLUGIN , /** sensor data provided by mjcb_sensor callback */ mjSENS_USER , } /** computation stage */ export enum mjtStage { /** no computations */ mjSTAGE_NONE , /** position-dependent computations */ mjSTAGE_POS , /** velocity-dependent computations */ mjSTAGE_VEL , /** acceleration/force-dependent computations */ mjSTAGE_ACC , } /** data type for sensors */ export enum mjtDataType { /** real values, no constraints */ mjDATATYPE_REAL , /** positive values; 0 or negative: inactive */ mjDATATYPE_POSITIVE , /** 3D unit vector */ mjDATATYPE_AXIS , /** unit quaternion */ mjDATATYPE_QUATERNION , } /** data fields returned by contact sensors */ export enum mjtConDataField { /** whether a contact was found */ mjCONDATA_FOUND , /** contact force */ mjCONDATA_FORCE , /** contact torque */ mjCONDATA_TORQUE , /** contact penetration distance */ mjCONDATA_DIST , /** contact position */ mjCONDATA_POS , /** contact frame normal */ mjCONDATA_NORMAL , /** contact frame first tangent */ mjCONDATA_TANGENT , /** number of contact sensor data fields */ mjNCONDATA , } /** frame alignment of bodies with their children */ export enum mjtSameFrame { /** no alignment */ mjSAMEFRAME_NONE , /** frame is same as body frame */ mjSAMEFRAME_BODY , /** frame is same as inertial frame */ mjSAMEFRAME_INERTIA , /** frame orientation is same as body orientation */ mjSAMEFRAME_BODYROT , /** frame orientation is same as inertia orientation */ mjSAMEFRAME_INERTIAROT , } /** mode for actuator length range computation */ export enum mjtLRMode { /** do not process any actuators */ mjLRMODE_NONE , /** process muscle actuators */ mjLRMODE_MUSCLE , /** process muscle and user actuators */ mjLRMODE_MUSCLEUSER , /** process all actuators */ mjLRMODE_ALL , } /** mode for flex selfcollide */ export enum mjtFlexSelf { /** no self-collisions */ mjFLEXSELF_NONE , /** skip midphase, go directly to narrowphase */ mjFLEXSELF_NARROW , /** use BVH in midphase (if midphase enabled) */ mjFLEXSELF_BVH , /** use SAP in midphase */ mjFLEXSELF_SAP , /** choose between BVH and SAP automatically */ mjFLEXSELF_AUTO , } /** signed distance function (SDF) type */ export enum mjtSDFType { /** single SDF */ mjSDFTYPE_SINGLE , /** max(A, B) */ mjSDFTYPE_INTERSECTION , /** A - B */ mjSDFTYPE_MIDSURFACE , /** A + B + abs(max(A, B)) */ mjSDFTYPE_COLLISION , } export interface Model { new (filename : string) : Model; load_from_xml(str: string): Model; /** Free the memory associated with the model */ free(): void; /** Retrive various parameters of the current simulation */ getOptions(): any; // MODEL_INTERFACE /** number of generalized coordinates = dim(qpos)*/ nq : number; /** number of degrees of freedom = dim(qvel)*/ nv : number; /** number of actuators/controls = dim(ctrl)*/ nu : number; /** number of activation states = dim(act)*/ na : number; /** number of bodies*/ nbody : number; /** number of total bounding volumes in all bodies*/ nbvh : number; /** number of static bounding volumes (aabb stored in mjModel)*/ nbvhstatic : number; /** number of dynamic bounding volumes (aabb stored in mjData)*/ nbvhdynamic : number; /** number of total octree cells in all meshes*/ noct : number; /** number of joints*/ njnt : number; /** number of kinematic trees under world body*/ ntree : number; /** number of non-zeros in sparse inertia matrix*/ nM : number; /** number of non-zeros in sparse body-dof matrix*/ nB : number; /** number of non-zeros in sparse reduced dof-dof matrix*/ nC : number; /** number of non-zeros in sparse dof-dof matrix*/ nD : number; /** number of geoms*/ ngeom : number; /** number of sites*/ nsite : number; /** number of cameras*/ ncam : number; /** number of lights*/ nlight : number; /** number of flexes*/ nflex : number; /** number of dofs in all flexes*/ nflexnode : number; /** number of vertices in all flexes*/ nflexvert : number; /** number of edges in all flexes*/ nflexedge : number; /** number of elements in all flexes*/ nflexelem : number; /** number of element vertex ids in all flexes*/ nflexelemdata : number; /** number of element edge ids in all flexes*/ nflexelemedge : number; /** number of shell fragment vertex ids in all flexes*/ nflexshelldata : number; /** number of element-vertex pairs in all flexes*/ nflexevpair : number; /** number of vertices with texture coordinates*/ nflextexcoord : number; /** number of meshes*/ nmesh : number; /** number of vertices in all meshes*/ nmeshvert : number; /** number of normals in all meshes*/ nmeshnormal : number; /** number of texcoords in all meshes*/ nmeshtexcoord : number; /** number of triangular faces in all meshes*/ nmeshface : number; /** number of ints in mesh auxiliary data*/ nmeshgraph : number; /** number of polygons in all meshes*/ nmeshpoly : number; /** number of vertices in all polygons*/ nmeshpolyvert : number; /** number of polygons in vertex map*/ nmeshpolymap : number; /** number of skins*/ nskin : number; /** number of vertices in all skins*/ nskinvert : number; /** number of vertiex with texcoords in all skins*/ nskintexvert : number; /** number of triangular faces in all skins*/ nskinface : number; /** number of bones in all skins*/ nskinbone : number; /** number of vertices in all skin bones*/ nskinbonevert : number; /** number of heightfields*/ nhfield : number; /** number of data points in all heightfields*/ nhfielddata : number; /** number of textures*/ ntex : number; /** number of bytes in texture rgb data*/ ntexdata : number; /** number of materials*/ nmat : number; /** number of predefined geom pairs*/ npair : number; /** number of excluded geom pairs*/ nexclude : number; /** number of equality constraints*/ neq : number; /** number of tendons*/ ntendon : number; /** number of wrap objects in all tendon paths*/ nwrap : number; /** number of sensors*/ nsensor : number; /** number of numeric custom fields*/ nnumeric : number; /** number of mjtNums in all numeric fields*/ nnumericdata : number; /** number of text custom fields*/ ntext : number; /** number of mjtBytes in all text fields*/ ntextdata : number; /** number of tuple custom fields*/ ntuple : number; /** number of objects in all tuple fields*/ ntupledata : number; /** number of keyframes*/ nkey : number; /** number of mocap bodies*/ nmocap : number; /** number of plugin instances*/ nplugin : number; /** number of chars in all plugin config attributes*/ npluginattr : number; /** number of mjtNums in body_user*/ nuser_body : number; /** number of mjtNums in jnt_user*/ nuser_jnt : number; /** number of mjtNums in geom_user*/ nuser_geom : number; /** number of mjtNums in site_user*/ nuser_site : number; /** number of mjtNums in cam_user*/ nuser_cam : number; /** number of mjtNums in tendon_user*/ nuser_tendon : number; /** number of mjtNums in actuator_user*/ nuser_actuator : number; /** number of mjtNums in sensor_user*/ nuser_sensor : number; /** number of chars in all names*/ nnames : number; /** number of chars in all paths*/ npaths : number; /** number of slots in the names hash map*/ nnames_map : number; /** number of non-zeros in sparse actuator_moment matrix*/ nJmom : number; /** number of bodies with nonzero gravcomp*/ ngravcomp : number; /** number of potential equality-constraint rows*/ nemax : number; /** number of available rows in constraint Jacobian (legacy)*/ njmax : number; /** number of potential contacts in contact list (legacy)*/ nconmax : number; /** number of mjtNums reserved for the user*/ nuserdata : number; /** number of mjtNums in sensor data vector*/ nsensordata : number; /** number of mjtNums in plugin state vector*/ npluginstate : number; narena : number; nbuffer : number; /** id of body's parent (nbody x 1)*/ body_parentid : Int32Array; /** id of root above body (nbody x 1)*/ body_rootid : Int32Array; /** id of body that this body is welded to (nbody x 1)*/ body_weldid : Int32Array; /** id of mocap data; -1: none (nbody x 1)*/ body_mocapid : Int32Array; /** number of joints for this body (nbody x 1)*/ body_jntnum : Int32Array; /** start addr of joints; -1: no joints (nbody x 1)*/ body_jntadr : Int32Array; /** number of motion degrees of freedom (nbody x 1)*/ body_dofnum : Int32Array; /** start addr of dofs; -1: no dofs (nbody x 1)*/ body_dofadr : Int32Array; /** id of body's kinematic tree; -1: static (nbody x 1)*/ body_treeid : Int32Array; /** number of geoms (nbody x 1)*/ body_geomnum : Int32Array; /** start addr of geoms; -1: no geoms (nbody x 1)*/ body_geomadr : Int32Array; /** 1: diag M; 2: diag M, sliders only (nbody x 1)*/ body_simple : Uint8Array; /** same frame as inertia (mjtSameframe) (nbody x 1)*/ body_sameframe : Uint8Array; /** position offset rel. to parent body (nbody x 3)*/ body_pos : Float64Array; /** orientation offset rel. to parent body (nbody x 4)*/ body_quat : Float64Array; /** local position of center of mass (nbody x 3)*/ body_ipos : Float64Array; /** local orientation of inertia ellipsoid (nbody x 4)*/ body_iquat : Float64Array; /** mass (nbody x 1)*/ body_mass : Float64Array; /** mass of subtree starting at this body (nbody x 1)*/ body_subtreemass : Float64Array; /** diagonal inertia in ipos/iquat frame (nbody x 3)*/ body_inertia : Float64Array; /** mean inv inert in qpos0 (trn, rot) (nbody x 2)*/ body_invweight0 : Float64Array; /** antigravity force, units of body weight (nbody x 1)*/ body_gravcomp : Float64Array; /** MAX over all geom margins (nbody x 1)*/ body_margin : Float64Array; /** user data (nbody x nuser_body)*/ body_user : Float64Array; /** plugin instance id; -1: not in use (nbody x 1)*/ body_plugin : Int32Array; /** OR over all geom contypes (nbody x 1)*/ body_contype : Int32Array; /** OR over all geom conaffinities (nbody x 1)*/ body_conaffinity : Int32Array; /** address of bvh root (nbody x 1)*/ body_bvhadr : Int32Array; /** number of bounding volumes (nbody x 1)*/ body_bvhnum : Int32Array; /** type of joint (mjtJoint) (njnt x 1)*/ jnt_type : Int32Array; /** start addr in 'qpos' for joint's data (njnt x 1)*/ jnt_qposadr : Int32Array; /** start addr in 'qvel' for joint's data (njnt x 1)*/ jnt_dofadr : Int32Array; /** id of joint's body (njnt x 1)*/ jnt_bodyid : Int32Array; /** group for visibility (njnt x 1)*/ jnt_group : Int32Array; /** does joint have limits (njnt x 1)*/ jnt_limited : Uint8Array; /** does joint have actuator force limits (njnt x 1)*/ jnt_actfrclimited : Uint8Array; /** is gravcomp force applied via actuators (njnt x 1)*/ jnt_actgravcomp : Uint8Array; /** constraint solver reference: limit (njnt x mjNREF)*/ jnt_solref : Float64Array; /** constraint solver impedance: limit (njnt x mjNIMP)*/ jnt_solimp : Float64Array; /** local anchor position (njnt x 3)*/ jnt_pos : Float64Array; /** local joint axis (njnt x 3)*/ jnt_axis : Float64Array; /** stiffness coefficient (njnt x 1)*/ jnt_stiffness : Float64Array; /** joint limits (njnt x 2)*/ jnt_range : Float64Array; /** range of total actuator force (njnt x 2)*/ jnt_actfrcrange : Float64Array; /** min distance for limit detection (njnt x 1)*/ jnt_margin : Float64Array; /** user data (njnt x nuser_jnt)*/ jnt_user : Float64Array; /** id of dof's body (nv x 1)*/ dof_bodyid : Int32Array; /** id of dof's joint (nv x 1)*/ dof_jntid : Int32Array; /** id of dof's parent; -1: none (nv x 1)*/ dof_parentid : Int32Array; /** id of dof's kinematic tree (nv x 1)*/ dof_treeid : Int32Array; /** dof address in M-diagonal (nv x 1)*/ dof_Madr : Int32Array; /** number of consecutive simple dofs (nv x 1)*/ dof_simplenum : Int32Array; /** constraint solver reference:frictionloss (nv x mjNREF)*/ dof_solref : Float64Array; /** constraint solver impedance:frictionloss (nv x mjNIMP)*/ dof_solimp : Float64Array; /** dof friction loss (nv x 1)*/ dof_frictionloss : Float64Array; /** dof armature inertia/mass (nv x 1)*/ dof_armature : Float64Array; /** damping coefficient (nv x 1)*/ dof_damping : Float64Array; /** diag. inverse inertia in qpos0 (nv x 1)*/ dof_invweight0 : Float64Array; /** diag. inertia in qpos0 (nv x 1)*/ dof_M0 : Float64Array; /** geometric type (mjtGeom) (ngeom x 1)*/ geom_type : Int32Array; /** geom contact type (ngeom x 1)*/ geom_contype : Int32Array; /** geom contact affinity (ngeom x 1)*/ geom_conaffinity : Int32Array; /** contact dimensionality (1, 3, 4, 6) (ngeom x 1)*/ geom_condim : Int32Array; /** id of geom's body (ngeom x 1)*/ geom_bodyid : Int32Array; /** id of geom's mesh/hfield; -1: none (ngeom x 1)*/ geom_dataid : Int32Array; /** material id for rendering; -1: none (ngeom x 1)*/ geom_matid : Int32Array; /** group for visibility (ngeom x 1)*/ geom_group : Int32Array; /** geom contact priority (ngeom x 1)*/ geom_priority : Int32Array; /** plugin instance id; -1: not in use (ngeom x 1)*/ geom_plugin : Int32Array; /** same frame as body (mjtSameframe) (ngeom x 1)*/ geom_sameframe : Uint8Array; /** mixing coef for solref/imp in geom pair (ngeom x 1)*/ geom_solmix : Float64Array; /** constraint solver reference: contact (ngeom x mjNREF)*/ geom_solref : Float64Array; /** constraint solver impedance: contact (ngeom x mjNIMP)*/ geom_solimp : Float64Array; /** geom-specific size parameters (ngeom x 3)*/ geom_size : Float64Array; /** bounding box, (center, size) (ngeom x 6)*/ geom_aabb : Float64Array; /** radius of bounding sphere (ngeom x 1)*/ geom_rbound : Float64Array; /** local position offset rel. to body (ngeom x 3)*/ geom_pos : Float64Array; /** local orientation offset rel. to body (ngeom x 4)*/ geom_quat : Float64Array; /** friction for (slide, spin, roll) (ngeom x 3)*/ geom_friction : Float64Array; /** detect contact if distmocap when selected body is mocap, and in d->qpos otherwise * d->qpos written only if flg_paused and subtree root for selected body has free joint */ applyPose(bodyID: number, refPosX : number, refPosY : number, refPosZ : number, refQuat1: number, refQuat2: number, refQuat3: number, refQuat4: number, flg_paused: number): void; // DATA_INTERFACE freeLastXML (): void; step (): void; step1 (): void; step2 (): void; forward (): void; inverse (): void; forwardSkip (skipstage : number, skipsensor : number): void; inverseSkip (skipstage : number, skipsensor : number): void; defaultSolRefImp (solref : Float64Array, solimp : Float64Array): void; deleteModel (): void; sizeModel (): number; resetData (): void; resetDataDebug (debug_value : string): void; resetDataKeyframe (key : number): void; markStack (): void; freeStack (): void; deleteData (): void; resetCallbacks (): void; setConst (): void; printFormattedModel (filename : string, float_format : string): void; printModel (filename : string): void; printFormattedData (filename : string, float_format : string): void; printData (filename : string): void; fwdPosition (): void; fwdVelocity (): void; fwdActuation (): void; fwdAcceleration (): void; fwdConstraint (): void; Euler (): void; RungeKutta (N : number): void; implicit (): void; invPosition (): void; invVelocity (): void; invConstraint (): void; compareFwdInv (): void; sensorPos (): void; sensorVel (): void; sensorAcc (): void; energyPos (): void; energyVel (): void; checkPos (): void; checkVel (): void; checkAcc (): void; kinematics (): void; comPos (): void; camlight (): void; flex (): void; tendon (): void; transmission (): void; crbCalculate (): void; makeM (): void; factorM (): void; solveM (x : Float64Array, y : Float64Array, n : number): void; solveM2 (x : Float64Array, y : Float64Array, sqrtInvD : Float64Array, n : number): void; comVel (): void; passive (): void; subtreeVel (): void; rne (flg_acc : number, result : Float64Array): void; rnePostConstraint (): void; collision (): void; makeConstraint (): void; island (): void; projectConstraint (): void; referenceConstraint (): void; stateSize (sig : unsigned ): number; getState (state : Float64Array, sig : unsigned ): void; setState (state : Float64Array, sig : unsigned ): void; setKeyframe (k : number): void; isPyramidal (): number; isSparse (): number; isDual (): number; mulJacVec (res : Float64Array, vec : Float64Array): void; mulJacTVec (res : Float64Array, vec : Float64Array): void; jacBody (jacp : Float64Array, jacr : Float64Array, body : number): void; jacBodyCom (jacp : Float64Array, jacr : Float64Array, body : number): void; jacSubtreeCom (jacp : Float64Array, body : number): void; jacGeom (jacp : Float64Array, jacr : Float64Array, geom : number): void; jacSite (jacp : Float64Array, jacr : Float64Array, site : number): void; angmomMat (mat : Float64Array, body : number): void; name2id (type : number, name : string): number; id2name (type : number, id : number): string; fullM (dst : Float64Array, M : Float64Array): void; mulM (res : Float64Array, vec : Float64Array): void; mulM2 (res : Float64Array, vec : Float64Array): void; differentiatePos (qvel : Float64Array, dt : number, qpos1 : Float64Array, qpos2 : Float64Array): void; integratePos (qpos : Float64Array, qvel : Float64Array, dt : number): void; normalizeQuat (qpos : Float64Array): void; getTotalmass (): number; setTotalmass (newmass : number): void; getPluginConfig (plugin_id : number, attrib : string): string; loadPluginLibrary (path : string): void; version (): number; versionString (): string; warning (warning : number, info : number): void; /** position (nq x 1)*/ qpos : Float64Array; /** velocity (nv x 1)*/ qvel : Float64Array; /** actuator activation (na x 1)*/ act : Float64Array; /** acceleration used for warmstart (nv x 1)*/ qacc_warmstart : Float64Array; /** plugin state (npluginstate x 1)*/ plugin_state : Float64Array; /** control (nu x 1)*/ ctrl : Float64Array; /** applied generalized force (nv x 1)*/ qfrc_applied : Float64Array; /** applied Cartesian force/torque (nbody x 6)*/ xfrc_applied : Float64Array; /** enable/disable constraints (neq x 1)*/ eq_active : Uint8Array; /** positions of mocap bodies (nmocap x 3)*/ mocap_pos : Float64Array; /** orientations of mocap bodies (nmocap x 4)*/ mocap_quat : Float64Array; /** acceleration (nv x 1)*/ qacc : Float64Array; /** time-derivative of actuator activation (na x 1)*/ act_dot : Float64Array; /** user data, not touched by engine (nuserdata x 1)*/ userdata : Float64Array; /** sensor data array (nsensordata x 1)*/ sensordata : Float64Array; /** copy of m->plugin, required for deletion (nplugin x 1)*/ plugin : Int32Array; /** pointer to plugin-managed data structure (nplugin x 1)*/ plugin_data : BigUint64Array; /** Cartesian position of body frame (nbody x 3)*/ xpos : Float64Array; /** Cartesian orientation of body frame (nbody x 4)*/ xquat : Float64Array; /** Cartesian orientation of body frame (nbody x 9)*/ xmat : Float64Array; /** Cartesian position of body com (nbody x 3)*/ xipos : Float64Array; /** Cartesian orientation of body inertia (nbody x 9)*/ ximat : Float64Array; /** Cartesian position of joint anchor (njnt x 3)*/ xanchor : Float64Array; /** Cartesian joint axis (njnt x 3)*/ xaxis : Float64Array; /** Cartesian geom position (ngeom x 3)*/ geom_xpos : Float64Array; /** Cartesian geom orientation (ngeom x 9)*/ geom_xmat : Float64Array; /** Cartesian site position (nsite x 3)*/ site_xpos : Float64Array; /** Cartesian site orientation (nsite x 9)*/ site_xmat : Float64Array; /** Cartesian camera position (ncam x 3)*/ cam_xpos : Float64Array; /** Cartesian camera orientation (ncam x 9)*/ cam_xmat : Float64Array; /** Cartesian light position (nlight x 3)*/ light_xpos : Float64Array; /** Cartesian light direction (nlight x 3)*/ light_xdir : Float64Array; /** center of mass of each subtree (nbody x 3)*/ subtree_com : Float64Array; /** com-based motion axis of each dof (rot:lin) (nv x 6)*/ cdof : Float64Array; /** com-based body inertia and mass (nbody x 10)*/ cinert : Float64Array; /** Cartesian flex vertex positions (nflexvert x 3)*/ flexvert_xpos : Float64Array; /** flex element bounding boxes (center, size) (nflexelem x 6)*/ flexelem_aabb : Float64Array; /** number of non-zeros in Jacobian row (nflexedge x 1)*/ flexedge_J_rownnz : Int32Array; /** row start address in colind array (nflexedge x 1)*/ flexedge_J_rowadr : Int32Array; /** column indices in sparse Jacobian (nflexedge x nv)*/ flexedge_J_colind : Int32Array; /** flex edge Jacobian (nflexedge x nv)*/ flexedge_J : Float64Array; /** flex edge lengths (nflexedge x 1)*/ flexedge_length : Float64Array; /** global bounding box (center, size) (nbvhdynamic x 6)*/ bvh_aabb_dyn : Float64Array; /** start address of tendon's path (ntendon x 1)*/ ten_wrapadr : Int32Array; /** number of wrap points in path (ntendon x 1)*/ ten_wrapnum : Int32Array; /** number of non-zeros in Jacobian row (ntendon x 1)*/ ten_J_rownnz : Int32Array; /** row start address in colind array (ntendon x 1)*/ ten_J_rowadr : Int32Array; /** column indices in sparse Jacobian (ntendon x nv)*/ ten_J_colind : Int32Array; /** tendon Jacobian (ntendon x nv)*/ ten_J : Float64Array; /** tendon lengths (ntendon x 1)*/ ten_length : Float64Array; /** geom id; -1: site; -2: pulley (nwrap x 2)*/ wrap_obj : Int32Array; /** Cartesian 3D points in all paths (nwrap x 6)*/ wrap_xpos : Float64Array; /** actuator lengths (nu x 1)*/ actuator_length : Float64Array; /** number of non-zeros in actuator_moment row (nu x 1)*/ moment_rownnz : Int32Array; /** row start address in colind array (nu x 1)*/ moment_rowadr : Int32Array; /** column indices in sparse Jacobian (nJmom x 1)*/ moment_colind : Int32Array; /** actuator moments (nJmom x 1)*/ actuator_moment : Float64Array; /** com-based composite inertia and mass (nbody x 10)*/ crb : Float64Array; /** inertia (sparse) (nM x 1)*/ qM : Float64Array; /** inertia (sparse) (nM x 1)*/ M : Float64Array; /** L'*D*L factorization of M (sparse) (nC x 1)*/ qLD : Float64Array; /** 1/diag(D) (nv x 1)*/ qLDiagInv : Float64Array; /** was bounding volume checked for collision (nbvh x 1)*/ bvh_active : Uint8Array; /** flex edge velocities (nflexedge x 1)*/ flexedge_velocity : Float64Array; /** tendon velocities (ntendon x 1)*/ ten_velocity : Float64Array; /** actuator velocities (nu x 1)*/ actuator_velocity : Float64Array; /** com-based velocity (rot:lin) (nbody x 6)*/ cvel : Float64Array; /** time-derivative of cdof (rot:lin) (nv x 6)*/ cdof_dot : Float64Array; /** C(qpos,qvel) (nv x 1)*/ qfrc_bias : Float64Array; /** passive spring force (nv x 1)*/ qfrc_spring : Float64Array; /** passive damper force (nv x 1)*/ qfrc_damper : Float64Array; /** passive gravity compensation force (nv x 1)*/ qfrc_gravcomp : Float64Array; /** passive fluid force (nv x 1)*/ qfrc_fluid : Float64Array; /** total passive force (nv x 1)*/ qfrc_passive : Float64Array; /** linear velocity of subtree com (nbody x 3)*/ subtree_linvel : Float64Array; /** angular momentum about subtree com (nbody x 3)*/ subtree_angmom : Float64Array; /** L'*D*L factorization of modified M (nC x 1)*/ qH : Float64Array; /** 1/diag(D) of modified M (nv x 1)*/ qHDiagInv : Float64Array; /** d (passive + actuator - bias) / d qvel (nD x 1)*/ qDeriv : Float64Array; /** sparse LU of (qM - dt*qDeriv) (nD x 1)*/ qLU : Float64Array; /** actuator force in actuation space (nu x 1)*/ actuator_force : Float64Array; /** actuator force (nv x 1)*/ qfrc_actuator : Float64Array; /** net unconstrained force (nv x 1)*/ qfrc_smooth : Float64Array; /** unconstrained acceleration (nv x 1)*/ qacc_smooth : Float64Array; /** constraint force (nv x 1)*/ qfrc_constraint : Float64Array; /** net external force; should equal:*/ qfrc_inverse : Float64Array; /** com-based acceleration (nbody x 6)*/ cacc : Float64Array; /** com-based interaction force with parent (nbody x 6)*/ cfrc_int : Float64Array; /** com-based external force on body (nbody x 6)*/ cfrc_ext : Float64Array; } export interface mujoco extends EmscriptenModule { FS : typeof FS; MEMFS : typeof MEMFS; Model : Model; State : State; Simulation : Simulation; mjtLightType: { /** spot */ mjLIGHT_SPOT : mjConstants; /** directional */ mjLIGHT_DIRECTIONAL : mjConstants; /** point */ mjLIGHT_POINT : mjConstants; /** image-based */ mjLIGHT_IMAGE : mjConstants; } mjtGeom: { /** plane */ mjGEOM_PLANE : mjConstants; /** height field */ mjGEOM_HFIELD : mjConstants; /** sphere */ mjGEOM_SPHERE : mjConstants; /** capsule */ mjGEOM_CAPSULE : mjConstants; /** ellipsoid */ mjGEOM_ELLIPSOID : mjConstants; /** cylinder */ mjGEOM_CYLINDER : mjConstants; /** box */ mjGEOM_BOX : mjConstants; /** mesh */ mjGEOM_MESH : mjConstants; /** signed distance field */ mjGEOM_SDF : mjConstants; /** number of regular geo metallic types */ mjNGEOMTYPES : mjConstants; /** arrow */ mjGEOM_ARROW : mjConstants; /** arrow without wedges */ mjGEOM_ARROW1 : mjConstants; /** arrow in both directions */ mjGEOM_ARROW2 : mjConstants; /** line */ mjGEOM_LINE : mjConstants; /** box with line edges */ mjGEOM_LINEBOX : mjConstants; /** flex */ mjGEOM_FLEX : mjConstants; /** skin */ mjGEOM_SKIN : mjConstants; /** text label */ mjGEOM_LABEL : mjConstants; /** triangle */ mjGEOM_TRIANGLE : mjConstants; /** missing geom type */ mjGEOM_NONE : mjConstants; }; mjtTextureRole: { /** unspecified */ mjTEXROLE_USER : mjConstants; /** base color (albedo) */ mjTEXROLE_RGB : mjConstants; /** ambient occlusion */ mjTEXROLE_OCCLUSION : mjConstants; /** roughness */ mjTEXROLE_ROUGHNESS : mjConstants; /** metallic */ mjTEXROLE_METALLIC : mjConstants; /** normal (bump) map */ mjTEXROLE_NORMAL : mjConstants; /** transperancy */ mjTEXROLE_OPACITY : mjConstants; /** light emission */ mjTEXROLE_EMISSIVE : mjConstants; /** base color, opacity */ mjTEXROLE_RGBA : mjConstants; /** occlusion, roughness, metallic */ mjTEXROLE_ORM : mjConstants; /** */ mjNTEXROLE : mjConstants; }; } declare var load_mujoco: EmscriptenModuleFactory; export default load_mujoco;