# Copyright 2023 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. # ============================================================================== """Provides information about MuJoCo API structs. DO NOT EDIT. THIS FILE IS AUTOMATICALLY GENERATED. """ from typing import Mapping from .ast_nodes import AnonymousStructDecl from .ast_nodes import AnonymousUnionDecl from .ast_nodes import ArrayType from .ast_nodes import PointerType from .ast_nodes import StructDecl from .ast_nodes import StructFieldDecl from .ast_nodes import ValueType STRUCTS: Mapping[str, StructDecl] = dict([ ('mjLROpt', StructDecl( name='mjLROpt', declname='struct mjLROpt_', fields=( StructFieldDecl( name='mode', type=ValueType(name='int'), doc='which actuators to process (mjtLRMode)', ), StructFieldDecl( name='useexisting', type=ValueType(name='int'), doc='use existing length range if available', ), StructFieldDecl( name='uselimit', type=ValueType(name='int'), doc='use joint and tendon limits if available', ), StructFieldDecl( name='accel', type=ValueType(name='mjtNum'), doc='target acceleration used to compute force', ), StructFieldDecl( name='maxforce', type=ValueType(name='mjtNum'), doc='maximum force; 0: no limit', ), StructFieldDecl( name='timeconst', type=ValueType(name='mjtNum'), doc='time constant for velocity reduction; min 0.01', ), StructFieldDecl( name='timestep', type=ValueType(name='mjtNum'), doc='simulation timestep; 0: use mjOption.timestep', ), StructFieldDecl( name='inttotal', type=ValueType(name='mjtNum'), doc='total simulation time interval', ), StructFieldDecl( name='interval', type=ValueType(name='mjtNum'), doc='evaluation time interval (at the end)', ), StructFieldDecl( name='tolrange', type=ValueType(name='mjtNum'), doc='convergence tolerance (relative to range)', ), ), )), ('mjVFS', StructDecl( name='mjVFS', declname='struct mjVFS_', fields=( StructFieldDecl( name='impl_', type=PointerType( inner_type=ValueType(name='void'), ), doc='internal pointer to VFS memory', ), ), )), ('mjOption', StructDecl( name='mjOption', declname='struct mjOption_', fields=( StructFieldDecl( name='timestep', type=ValueType(name='mjtNum'), doc='timestep', ), StructFieldDecl( name='apirate', type=ValueType(name='mjtNum'), doc='update rate for remote API (Hz)', ), StructFieldDecl( name='impratio', type=ValueType(name='mjtNum'), doc='ratio of friction-to-normal contact impedance', ), StructFieldDecl( name='tolerance', type=ValueType(name='mjtNum'), doc='main solver tolerance', ), StructFieldDecl( name='ls_tolerance', type=ValueType(name='mjtNum'), doc='CG/Newton linesearch tolerance', ), StructFieldDecl( name='noslip_tolerance', type=ValueType(name='mjtNum'), doc='noslip solver tolerance', ), StructFieldDecl( name='ccd_tolerance', type=ValueType(name='mjtNum'), doc='convex collision solver tolerance', ), StructFieldDecl( name='gravity', type=ArrayType( inner_type=ValueType(name='mjtNum'), extents=(3,), ), doc='gravitational acceleration', ), StructFieldDecl( name='wind', type=ArrayType( inner_type=ValueType(name='mjtNum'), extents=(3,), ), doc='wind (for lift, drag and viscosity)', ), StructFieldDecl( name='magnetic', type=ArrayType( inner_type=ValueType(name='mjtNum'), extents=(3,), ), doc='global magnetic flux', ), StructFieldDecl( name='density', type=ValueType(name='mjtNum'), doc='density of medium', ), StructFieldDecl( name='viscosity', type=ValueType(name='mjtNum'), doc='viscosity of medium', ), StructFieldDecl( name='o_margin', type=ValueType(name='mjtNum'), doc='margin', ), StructFieldDecl( name='o_solref', type=ArrayType( inner_type=ValueType(name='mjtNum'), extents=(2,), ), doc='solref', ), StructFieldDecl( name='o_solimp', type=ArrayType( inner_type=ValueType(name='mjtNum'), extents=(5,), ), doc='solimp', ), StructFieldDecl( name='o_friction', type=ArrayType( inner_type=ValueType(name='mjtNum'), extents=(5,), ), doc='friction', ), StructFieldDecl( name='integrator', type=ValueType(name='int'), doc='integration mode (mjtIntegrator)', ), StructFieldDecl( name='cone', type=ValueType(name='int'), doc='type of friction cone (mjtCone)', ), StructFieldDecl( name='jacobian', type=ValueType(name='int'), doc='type of Jacobian (mjtJacobian)', ), StructFieldDecl( name='solver', type=ValueType(name='int'), doc='solver algorithm (mjtSolver)', ), StructFieldDecl( name='iterations', type=ValueType(name='int'), doc='maximum number of main solver iterations', ), StructFieldDecl( name='ls_iterations', type=ValueType(name='int'), doc='maximum number of CG/Newton linesearch iterations', ), StructFieldDecl( name='noslip_iterations', type=ValueType(name='int'), doc='maximum number of noslip solver iterations', ), StructFieldDecl( name='ccd_iterations', type=ValueType(name='int'), doc='maximum number of convex collision solver iterations', ), StructFieldDecl( name='disableflags', type=ValueType(name='int'), doc='bit flags for disabling standard features', ), StructFieldDecl( name='enableflags', type=ValueType(name='int'), doc='bit flags for enabling optional features', ), StructFieldDecl( name='disableactuator', type=ValueType(name='int'), doc='bit flags for disabling actuators by group id', ), StructFieldDecl( name='sdf_initpoints', type=ValueType(name='int'), doc='number of starting points for gradient descent', ), StructFieldDecl( name='sdf_iterations', type=ValueType(name='int'), doc='max number of iterations for gradient descent', ), ), )), ('mjVisual', StructDecl( name='mjVisual', declname='struct mjVisual_', fields=( StructFieldDecl( name='global', type=AnonymousStructDecl( fields=( StructFieldDecl( name='orthographic', type=ValueType(name='int'), doc='is the free camera orthographic (0: no, 1: yes)', # pylint: disable=line-too-long ), StructFieldDecl( name='fovy', type=ValueType(name='float'), doc='y field-of-view of free camera (orthographic ? length : degree)', # pylint: disable=line-too-long ), StructFieldDecl( name='ipd', type=ValueType(name='float'), doc='inter-pupilary distance for free camera', ), StructFieldDecl( name='azimuth', type=ValueType(name='float'), doc='initial azimuth of free camera (degrees)', ), StructFieldDecl( name='elevation', type=ValueType(name='float'), doc='initial elevation of free camera (degrees)', ), StructFieldDecl( name='linewidth', type=ValueType(name='float'), doc='line width for wireframe and ray rendering', ), StructFieldDecl( name='glow', type=ValueType(name='float'), doc='glow coefficient for selected body', ), StructFieldDecl( name='realtime', type=ValueType(name='float'), doc='initial real-time factor (1: real time)', ), StructFieldDecl( name='offwidth', type=ValueType(name='int'), doc='width of offscreen buffer', ), StructFieldDecl( name='offheight', type=ValueType(name='int'), doc='height of offscreen buffer', ), StructFieldDecl( name='ellipsoidinertia', type=ValueType(name='int'), doc='geom for inertia visualization (0: box, 1: ellipsoid)', # pylint: disable=line-too-long ), StructFieldDecl( name='bvactive', type=ValueType(name='int'), doc='visualize active bounding volumes (0: no, 1: yes)', # pylint: disable=line-too-long ), ), ), doc='', ), StructFieldDecl( name='quality', type=AnonymousStructDecl( fields=( StructFieldDecl( name='shadowsize', type=ValueType(name='int'), doc='size of shadowmap texture', ), StructFieldDecl( name='offsamples', type=ValueType(name='int'), doc='number of multisamples for offscreen rendering', # pylint: disable=line-too-long ), StructFieldDecl( name='numslices', type=ValueType(name='int'), doc='number of slices for builtin geom drawing', ), StructFieldDecl( name='numstacks', type=ValueType(name='int'), doc='number of stacks for builtin geom drawing', ), StructFieldDecl( name='numquads', type=ValueType(name='int'), doc='number of quads for box rendering', ), ), ), doc='', ), StructFieldDecl( name='headlight', type=AnonymousStructDecl( fields=( StructFieldDecl( name='ambient', type=ArrayType( inner_type=ValueType(name='float'), extents=(3,), ), doc='ambient rgb (alpha=1)', ), StructFieldDecl( name='diffuse', type=ArrayType( inner_type=ValueType(name='float'), extents=(3,), ), doc='diffuse rgb (alpha=1)', ), StructFieldDecl( name='specular', type=ArrayType( inner_type=ValueType(name='float'), extents=(3,), ), doc='specular rgb (alpha=1)', ), StructFieldDecl( name='active', type=ValueType(name='int'), doc='is headlight active', ), ), ), doc='', ), StructFieldDecl( name='map', type=AnonymousStructDecl( fields=( StructFieldDecl( name='stiffness', type=ValueType(name='float'), doc='mouse perturbation stiffness (space->force)', ), StructFieldDecl( name='stiffnessrot', type=ValueType(name='float'), doc='mouse perturbation stiffness (space->torque)', ), StructFieldDecl( name='force', type=ValueType(name='float'), doc='from force units to space units', ), StructFieldDecl( name='torque', type=ValueType(name='float'), doc='from torque units to space units', ), StructFieldDecl( name='alpha', type=ValueType(name='float'), doc='scale geom alphas when transparency is enabled', # pylint: disable=line-too-long ), StructFieldDecl( name='fogstart', type=ValueType(name='float'), doc='OpenGL fog starts at fogstart * mjModel.stat.extent', # pylint: disable=line-too-long ), StructFieldDecl( name='fogend', type=ValueType(name='float'), doc='OpenGL fog ends at fogend * mjModel.stat.extent', # pylint: disable=line-too-long ), StructFieldDecl( name='znear', type=ValueType(name='float'), doc='near clipping plane = znear * mjModel.stat.extent', # pylint: disable=line-too-long ), StructFieldDecl( name='zfar', type=ValueType(name='float'), doc='far clipping plane = zfar * mjModel.stat.extent', # pylint: disable=line-too-long ), StructFieldDecl( name='haze', type=ValueType(name='float'), doc='haze ratio', ), StructFieldDecl( name='shadowclip', type=ValueType(name='float'), doc='directional light: shadowclip * mjModel.stat.extent', # pylint: disable=line-too-long ), StructFieldDecl( name='shadowscale', type=ValueType(name='float'), doc='spot light: shadowscale * light.cutoff', ), StructFieldDecl( name='actuatortendon', type=ValueType(name='float'), doc='scale tendon width', ), ), ), doc='', ), StructFieldDecl( name='scale', type=AnonymousStructDecl( fields=( StructFieldDecl( name='forcewidth', type=ValueType(name='float'), doc='width of force arrow', ), StructFieldDecl( name='contactwidth', type=ValueType(name='float'), doc='contact width', ), StructFieldDecl( name='contactheight', type=ValueType(name='float'), doc='contact height', ), StructFieldDecl( name='connect', type=ValueType(name='float'), doc='autoconnect capsule width', ), StructFieldDecl( name='com', type=ValueType(name='float'), doc='com radius', ), StructFieldDecl( name='camera', type=ValueType(name='float'), doc='camera object', ), StructFieldDecl( name='light', type=ValueType(name='float'), doc='light object', ), StructFieldDecl( name='selectpoint', type=ValueType(name='float'), doc='selection point', ), StructFieldDecl( name='jointlength', type=ValueType(name='float'), doc='joint length', ), StructFieldDecl( name='jointwidth', type=ValueType(name='float'), doc='joint width', ), StructFieldDecl( name='actuatorlength', type=ValueType(name='float'), doc='actuator length', ), StructFieldDecl( name='actuatorwidth', type=ValueType(name='float'), doc='actuator width', ), StructFieldDecl( name='framelength', type=ValueType(name='float'), doc='bodyframe axis length', ), StructFieldDecl( name='framewidth', type=ValueType(name='float'), doc='bodyframe axis width', ), StructFieldDecl( name='constraint', type=ValueType(name='float'), doc='constraint width', ), StructFieldDecl( name='slidercrank', type=ValueType(name='float'), doc='slidercrank width', ), StructFieldDecl( name='frustum', type=ValueType(name='float'), doc='frustum zfar plane', ), ), ), doc='', ), StructFieldDecl( name='rgba', type=AnonymousStructDecl( fields=( StructFieldDecl( name='fog', type=ArrayType( inner_type=ValueType(name='float'), extents=(4,), ), doc='fog', ), StructFieldDecl( name='haze', type=ArrayType( inner_type=ValueType(name='float'), extents=(4,), ), doc='haze', ), StructFieldDecl( name='force', type=ArrayType( inner_type=ValueType(name='float'), extents=(4,), ), doc='external force', ), StructFieldDecl( name='inertia', type=ArrayType( inner_type=ValueType(name='float'), extents=(4,), ), doc='inertia box', ), StructFieldDecl( name='joint', type=ArrayType( inner_type=ValueType(name='float'), extents=(4,), ), doc='joint', ), StructFieldDecl( name='actuator', type=ArrayType( inner_type=ValueType(name='float'), extents=(4,), ), doc='actuator, neutral', ), StructFieldDecl( name='actuatornegative', type=ArrayType( inner_type=ValueType(name='float'), extents=(4,), ), doc='actuator, negative limit', ), StructFieldDecl( name='actuatorpositive', type=ArrayType( inner_type=ValueType(name='float'), extents=(4,), ), doc='actuator, positive limit', ), StructFieldDecl( name='com', type=ArrayType( inner_type=ValueType(name='float'), extents=(4,), ), doc='center of mass', ), StructFieldDecl( name='camera', type=ArrayType( inner_type=ValueType(name='float'), extents=(4,), ), doc='camera object', ), StructFieldDecl( name='light', type=ArrayType( inner_type=ValueType(name='float'), extents=(4,), ), doc='light object', ), StructFieldDecl( name='selectpoint', type=ArrayType( inner_type=ValueType(name='float'), extents=(4,), ), doc='selection point', ), StructFieldDecl( name='connect', type=ArrayType( inner_type=ValueType(name='float'), extents=(4,), ), doc='auto connect', ), StructFieldDecl( name='contactpoint', type=ArrayType( inner_type=ValueType(name='float'), extents=(4,), ), doc='contact point', ), StructFieldDecl( name='contactforce', type=ArrayType( inner_type=ValueType(name='float'), extents=(4,), ), doc='contact force', ), StructFieldDecl( name='contactfriction', type=ArrayType( inner_type=ValueType(name='float'), extents=(4,), ), doc='contact friction force', ), StructFieldDecl( name='contacttorque', type=ArrayType( inner_type=ValueType(name='float'), extents=(4,), ), doc='contact torque', ), StructFieldDecl( name='contactgap', type=ArrayType( inner_type=ValueType(name='float'), extents=(4,), ), doc='contact point in gap', ), StructFieldDecl( name='rangefinder', type=ArrayType( inner_type=ValueType(name='float'), extents=(4,), ), doc='rangefinder ray', ), StructFieldDecl( name='constraint', type=ArrayType( inner_type=ValueType(name='float'), extents=(4,), ), doc='constraint', ), StructFieldDecl( name='slidercrank', type=ArrayType( inner_type=ValueType(name='float'), extents=(4,), ), doc='slidercrank', ), StructFieldDecl( name='crankbroken', type=ArrayType( inner_type=ValueType(name='float'), extents=(4,), ), doc='used when crank must be stretched/broken', ), StructFieldDecl( name='frustum', type=ArrayType( inner_type=ValueType(name='float'), extents=(4,), ), doc='camera frustum', ), StructFieldDecl( name='bv', type=ArrayType( inner_type=ValueType(name='float'), extents=(4,), ), doc='bounding volume', ), StructFieldDecl( name='bvactive', type=ArrayType( inner_type=ValueType(name='float'), extents=(4,), ), doc='active bounding volume', ), ), ), doc='', ), ), )), ('mjStatistic', StructDecl( name='mjStatistic', declname='struct mjStatistic_', fields=( StructFieldDecl( name='meaninertia', type=ValueType(name='mjtNum'), doc='mean diagonal inertia', ), StructFieldDecl( name='meanmass', type=ValueType(name='mjtNum'), doc='mean body mass', ), StructFieldDecl( name='meansize', type=ValueType(name='mjtNum'), doc='mean body size', ), StructFieldDecl( name='extent', type=ValueType(name='mjtNum'), doc='spatial extent', ), StructFieldDecl( name='center', type=ArrayType( inner_type=ValueType(name='mjtNum'), extents=(3,), ), doc='center of model', ), ), )), ('mjModel', StructDecl( name='mjModel', declname='struct mjModel_', fields=( StructFieldDecl( name='nq', type=ValueType(name='int'), doc='number of generalized coordinates = dim(qpos)', ), StructFieldDecl( name='nv', type=ValueType(name='int'), doc='number of degrees of freedom = dim(qvel)', ), StructFieldDecl( name='nu', type=ValueType(name='int'), doc='number of actuators/controls = dim(ctrl)', ), StructFieldDecl( name='na', type=ValueType(name='int'), doc='number of activation states = dim(act)', ), StructFieldDecl( name='nbody', type=ValueType(name='int'), doc='number of bodies', ), StructFieldDecl( name='nbvh', type=ValueType(name='int'), doc='number of total bounding volumes in all bodies', ), StructFieldDecl( name='nbvhstatic', type=ValueType(name='int'), doc='number of static bounding volumes (aabb stored in mjModel)', # pylint: disable=line-too-long ), StructFieldDecl( name='nbvhdynamic', type=ValueType(name='int'), doc='number of dynamic bounding volumes (aabb stored in mjData)', # pylint: disable=line-too-long ), StructFieldDecl( name='njnt', type=ValueType(name='int'), doc='number of joints', ), StructFieldDecl( name='ngeom', type=ValueType(name='int'), doc='number of geoms', ), StructFieldDecl( name='nsite', type=ValueType(name='int'), doc='number of sites', ), StructFieldDecl( name='ncam', type=ValueType(name='int'), doc='number of cameras', ), StructFieldDecl( name='nlight', type=ValueType(name='int'), doc='number of lights', ), StructFieldDecl( name='nflex', type=ValueType(name='int'), doc='number of flexes', ), StructFieldDecl( name='nflexvert', type=ValueType(name='int'), doc='number of vertices in all flexes', ), StructFieldDecl( name='nflexedge', type=ValueType(name='int'), doc='number of edges in all flexes', ), StructFieldDecl( name='nflexelem', type=ValueType(name='int'), doc='number of elements in all flexes', ), StructFieldDecl( name='nflexelemdata', type=ValueType(name='int'), doc='number of element vertex ids in all flexes', ), StructFieldDecl( name='nflexelemedge', type=ValueType(name='int'), doc='number of element edge ids in all flexes', ), StructFieldDecl( name='nflexshelldata', type=ValueType(name='int'), doc='number of shell fragment vertex ids in all flexes', ), StructFieldDecl( name='nflexevpair', type=ValueType(name='int'), doc='number of element-vertex pairs in all flexes', ), StructFieldDecl( name='nflextexcoord', type=ValueType(name='int'), doc='number of vertices with texture coordinates', ), StructFieldDecl( name='nmesh', type=ValueType(name='int'), doc='number of meshes', ), StructFieldDecl( name='nmeshvert', type=ValueType(name='int'), doc='number of vertices in all meshes', ), StructFieldDecl( name='nmeshnormal', type=ValueType(name='int'), doc='number of normals in all meshes', ), StructFieldDecl( name='nmeshtexcoord', type=ValueType(name='int'), doc='number of texcoords in all meshes', ), StructFieldDecl( name='nmeshface', type=ValueType(name='int'), doc='number of triangular faces in all meshes', ), StructFieldDecl( name='nmeshgraph', type=ValueType(name='int'), doc='number of ints in mesh auxiliary data', ), StructFieldDecl( name='nskin', type=ValueType(name='int'), doc='number of skins', ), StructFieldDecl( name='nskinvert', type=ValueType(name='int'), doc='number of vertices in all skins', ), StructFieldDecl( name='nskintexvert', type=ValueType(name='int'), doc='number of vertiex with texcoords in all skins', ), StructFieldDecl( name='nskinface', type=ValueType(name='int'), doc='number of triangular faces in all skins', ), StructFieldDecl( name='nskinbone', type=ValueType(name='int'), doc='number of bones in all skins', ), StructFieldDecl( name='nskinbonevert', type=ValueType(name='int'), doc='number of vertices in all skin bones', ), StructFieldDecl( name='nhfield', type=ValueType(name='int'), doc='number of heightfields', ), StructFieldDecl( name='nhfielddata', type=ValueType(name='int'), doc='number of data points in all heightfields', ), StructFieldDecl( name='ntex', type=ValueType(name='int'), doc='number of textures', ), StructFieldDecl( name='ntexdata', type=ValueType(name='int'), doc='number of bytes in texture rgb data', ), StructFieldDecl( name='nmat', type=ValueType(name='int'), doc='number of materials', ), StructFieldDecl( name='npair', type=ValueType(name='int'), doc='number of predefined geom pairs', ), StructFieldDecl( name='nexclude', type=ValueType(name='int'), doc='number of excluded geom pairs', ), StructFieldDecl( name='neq', type=ValueType(name='int'), doc='number of equality constraints', ), StructFieldDecl( name='ntendon', type=ValueType(name='int'), doc='number of tendons', ), StructFieldDecl( name='nwrap', type=ValueType(name='int'), doc='number of wrap objects in all tendon paths', ), StructFieldDecl( name='nsensor', type=ValueType(name='int'), doc='number of sensors', ), StructFieldDecl( name='nnumeric', type=ValueType(name='int'), doc='number of numeric custom fields', ), StructFieldDecl( name='nnumericdata', type=ValueType(name='int'), doc='number of mjtNums in all numeric fields', ), StructFieldDecl( name='ntext', type=ValueType(name='int'), doc='number of text custom fields', ), StructFieldDecl( name='ntextdata', type=ValueType(name='int'), doc='number of mjtBytes in all text fields', ), StructFieldDecl( name='ntuple', type=ValueType(name='int'), doc='number of tuple custom fields', ), StructFieldDecl( name='ntupledata', type=ValueType(name='int'), doc='number of objects in all tuple fields', ), StructFieldDecl( name='nkey', type=ValueType(name='int'), doc='number of keyframes', ), StructFieldDecl( name='nmocap', type=ValueType(name='int'), doc='number of mocap bodies', ), StructFieldDecl( name='nplugin', type=ValueType(name='int'), doc='number of plugin instances', ), StructFieldDecl( name='npluginattr', type=ValueType(name='int'), doc='number of chars in all plugin config attributes', ), StructFieldDecl( name='nuser_body', type=ValueType(name='int'), doc='number of mjtNums in body_user', ), StructFieldDecl( name='nuser_jnt', type=ValueType(name='int'), doc='number of mjtNums in jnt_user', ), StructFieldDecl( name='nuser_geom', type=ValueType(name='int'), doc='number of mjtNums in geom_user', ), StructFieldDecl( name='nuser_site', type=ValueType(name='int'), doc='number of mjtNums in site_user', ), StructFieldDecl( name='nuser_cam', type=ValueType(name='int'), doc='number of mjtNums in cam_user', ), StructFieldDecl( name='nuser_tendon', type=ValueType(name='int'), doc='number of mjtNums in tendon_user', ), StructFieldDecl( name='nuser_actuator', type=ValueType(name='int'), doc='number of mjtNums in actuator_user', ), StructFieldDecl( name='nuser_sensor', type=ValueType(name='int'), doc='number of mjtNums in sensor_user', ), StructFieldDecl( name='nnames', type=ValueType(name='int'), doc='number of chars in all names', ), StructFieldDecl( name='nnames_map', type=ValueType(name='int'), doc='number of slots in the names hash map', ), StructFieldDecl( name='npaths', type=ValueType(name='int'), doc='number of chars in all paths', ), StructFieldDecl( name='nM', type=ValueType(name='int'), doc='number of non-zeros in sparse inertia matrix', ), StructFieldDecl( name='nB', type=ValueType(name='int'), doc='number of non-zeros in sparse body-dof matrix', ), StructFieldDecl( name='nC', type=ValueType(name='int'), doc='number of non-zeros in sparse reduced dof-dof matrix', ), StructFieldDecl( name='nD', type=ValueType(name='int'), doc='number of non-zeros in sparse dof-dof matrix', ), StructFieldDecl( name='ntree', type=ValueType(name='int'), doc='number of kinematic trees under world body', ), StructFieldDecl( name='ngravcomp', type=ValueType(name='int'), doc='number of bodies with nonzero gravcomp', ), StructFieldDecl( name='nemax', type=ValueType(name='int'), doc='number of potential equality-constraint rows', ), StructFieldDecl( name='njmax', type=ValueType(name='int'), doc='number of available rows in constraint Jacobian', ), StructFieldDecl( name='nconmax', type=ValueType(name='int'), doc='number of potential contacts in contact list', ), StructFieldDecl( name='nuserdata', type=ValueType(name='int'), doc='number of mjtNums reserved for the user', ), StructFieldDecl( name='nsensordata', type=ValueType(name='int'), doc='number of mjtNums in sensor data vector', ), StructFieldDecl( name='npluginstate', type=ValueType(name='int'), doc='number of mjtNums in plugin state vector', ), StructFieldDecl( name='narena', type=ValueType(name='size_t'), doc='number of bytes in the mjData arena (inclusive of stack)', ), StructFieldDecl( name='nbuffer', type=ValueType(name='size_t'), doc='number of bytes in buffer', ), StructFieldDecl( name='opt', type=ValueType(name='mjOption'), doc='physics options', ), StructFieldDecl( name='vis', type=ValueType(name='mjVisual'), doc='visualization options', ), StructFieldDecl( name='stat', type=ValueType(name='mjStatistic'), doc='model statistics', ), StructFieldDecl( name='buffer', type=PointerType( inner_type=ValueType(name='void'), ), doc='main buffer; all pointers point in it (nbuffer)', ), StructFieldDecl( name='qpos0', type=PointerType( inner_type=ValueType(name='mjtNum'), ), doc='qpos values at default pose', array_extent=('nq',), ), StructFieldDecl( name='qpos_spring', type=PointerType( inner_type=ValueType(name='mjtNum'), ), doc='reference pose for springs', array_extent=('nq',), ), StructFieldDecl( name='body_parentid', type=PointerType( inner_type=ValueType(name='int'), ), doc="id of body's parent", array_extent=('nbody',), ), StructFieldDecl( name='body_rootid', type=PointerType( inner_type=ValueType(name='int'), ), doc='id of root above body', array_extent=('nbody',), ), StructFieldDecl( name='body_weldid', type=PointerType( inner_type=ValueType(name='int'), ), doc='id of body that this body is welded to', array_extent=('nbody',), ), StructFieldDecl( name='body_mocapid', type=PointerType( inner_type=ValueType(name='int'), ), doc='id of mocap data; -1: none', array_extent=('nbody',), ), StructFieldDecl( name='body_jntnum', type=PointerType( inner_type=ValueType(name='int'), ), doc='number of joints for this body', array_extent=('nbody',), ), StructFieldDecl( name='body_jntadr', type=PointerType( inner_type=ValueType(name='int'), ), doc='start addr of joints; -1: no joints', array_extent=('nbody',), ), StructFieldDecl( name='body_dofnum', type=PointerType( inner_type=ValueType(name='int'), ), doc='number of motion degrees of freedom', array_extent=('nbody',), ), StructFieldDecl( name='body_dofadr', type=PointerType( inner_type=ValueType(name='int'), ), doc='start addr of dofs; -1: no dofs', array_extent=('nbody',), ), StructFieldDecl( name='body_treeid', type=PointerType( inner_type=ValueType(name='int'), ), doc="id of body's kinematic tree; -1: static", array_extent=('nbody',), ), StructFieldDecl( name='body_geomnum', type=PointerType( inner_type=ValueType(name='int'), ), doc='number of geoms', array_extent=('nbody',), ), StructFieldDecl( name='body_geomadr', type=PointerType( inner_type=ValueType(name='int'), ), doc='start addr of geoms; -1: no geoms', array_extent=('nbody',), ), StructFieldDecl( name='body_simple', type=PointerType( inner_type=ValueType(name='mjtByte'), ), doc='1: diag M; 2: diag M, sliders only', array_extent=('nbody',), ), StructFieldDecl( name='body_sameframe', type=PointerType( inner_type=ValueType(name='mjtByte'), ), doc='same frame as inertia (mjtSameframe)', array_extent=('nbody',), ), StructFieldDecl( name='body_pos', type=PointerType( inner_type=ValueType(name='mjtNum'), ), doc='position offset rel. to parent body', array_extent=('nbody', 3), ), StructFieldDecl( name='body_quat', type=PointerType( inner_type=ValueType(name='mjtNum'), ), doc='orientation offset rel. to parent body', array_extent=('nbody', 4), ), StructFieldDecl( name='body_ipos', type=PointerType( inner_type=ValueType(name='mjtNum'), ), doc='local position of center of mass', array_extent=('nbody', 3), ), StructFieldDecl( name='body_iquat', type=PointerType( inner_type=ValueType(name='mjtNum'), ), doc='local orientation of inertia ellipsoid', array_extent=('nbody', 4), ), StructFieldDecl( name='body_mass', type=PointerType( inner_type=ValueType(name='mjtNum'), ), doc='mass', array_extent=('nbody',), ), StructFieldDecl( name='body_subtreemass', type=PointerType( inner_type=ValueType(name='mjtNum'), ), doc='mass of subtree starting at this body', array_extent=('nbody',), ), StructFieldDecl( name='body_inertia', type=PointerType( inner_type=ValueType(name='mjtNum'), ), doc='diagonal inertia in ipos/iquat frame', array_extent=('nbody', 3), ), StructFieldDecl( name='body_invweight0', type=PointerType( inner_type=ValueType(name='mjtNum'), ), doc='mean inv inert in qpos0 (trn, rot)', array_extent=('nbody', 2), ), StructFieldDecl( name='body_gravcomp', type=PointerType( inner_type=ValueType(name='mjtNum'), ), doc='antigravity force, units of body weight', array_extent=('nbody',), ), StructFieldDecl( name='body_margin', type=PointerType( inner_type=ValueType(name='mjtNum'), ), doc='MAX over all geom margins', array_extent=('nbody',), ), StructFieldDecl( name='body_user', type=PointerType( inner_type=ValueType(name='mjtNum'), ), doc='user data', array_extent=('nbody', 'nuser_body'), ), StructFieldDecl( name='body_plugin', type=PointerType( inner_type=ValueType(name='int'), ), doc='plugin instance id; -1: not in use', array_extent=('nbody',), ), StructFieldDecl( name='body_contype', type=PointerType( inner_type=ValueType(name='int'), ), doc='OR over all geom contypes', array_extent=('nbody',), ), StructFieldDecl( name='body_conaffinity', type=PointerType( inner_type=ValueType(name='int'), ), doc='OR over all geom conaffinities', array_extent=('nbody',), ), StructFieldDecl( name='body_bvhadr', type=PointerType( inner_type=ValueType(name='int'), ), doc='address of bvh root', array_extent=('nbody',), ), StructFieldDecl( name='body_bvhnum', type=PointerType( inner_type=ValueType(name='int'), ), doc='number of bounding volumes', array_extent=('nbody',), ), StructFieldDecl( name='bvh_depth', type=PointerType( inner_type=ValueType(name='int'), ), doc='depth in the bounding volume hierarchy', array_extent=('nbvh',), ), StructFieldDecl( name='bvh_child', type=PointerType( inner_type=ValueType(name='int'), ), doc='left and right children in tree', array_extent=('nbvh', 2), ), StructFieldDecl( name='bvh_nodeid', type=PointerType( inner_type=ValueType(name='int'), ), doc='geom or elem id of node; -1: non-leaf', array_extent=('nbvh',), ), StructFieldDecl( name='bvh_aabb', type=PointerType( inner_type=ValueType(name='mjtNum'), ), doc='local bounding box (center, size)', array_extent=('nbvhstatic', 6), ), StructFieldDecl( name='jnt_type', type=PointerType( inner_type=ValueType(name='int'), ), doc='type of joint (mjtJoint)', array_extent=('njnt',), ), StructFieldDecl( name='jnt_qposadr', type=PointerType( inner_type=ValueType(name='int'), ), doc="start addr in 'qpos' for joint's data", array_extent=('njnt',), ), StructFieldDecl( name='jnt_dofadr', type=PointerType( inner_type=ValueType(name='int'), ), doc="start addr in 'qvel' for joint's data", array_extent=('njnt',), ), StructFieldDecl( name='jnt_bodyid', type=PointerType( inner_type=ValueType(name='int'), ), doc="id of joint's body", array_extent=('njnt',), ), StructFieldDecl( name='jnt_group', type=PointerType( inner_type=ValueType(name='int'), ), doc='group for visibility', array_extent=('njnt',), ), StructFieldDecl( name='jnt_limited', type=PointerType( inner_type=ValueType(name='mjtByte'), ), doc='does joint have limits', array_extent=('njnt',), ), StructFieldDecl( name='jnt_actfrclimited', type=PointerType( inner_type=ValueType(name='mjtByte'), ), doc='does joint have actuator force limits', array_extent=('njnt',), ), StructFieldDecl( name='jnt_actgravcomp', type=PointerType( inner_type=ValueType(name='mjtByte'), ), doc='is gravcomp force applied via actuators', array_extent=('njnt',), ), StructFieldDecl( name='jnt_solref', type=PointerType( inner_type=ValueType(name='mjtNum'), ), doc='constraint solver reference: limit', array_extent=('njnt', 'mjNREF'), ), StructFieldDecl( name='jnt_solimp', type=PointerType( inner_type=ValueType(name='mjtNum'), ), doc='constraint solver impedance: limit', array_extent=('njnt', 'mjNIMP'), ), StructFieldDecl( name='jnt_pos', type=PointerType( inner_type=ValueType(name='mjtNum'), ), doc='local anchor position', array_extent=('njnt', 3), ), StructFieldDecl( name='jnt_axis', type=PointerType( inner_type=ValueType(name='mjtNum'), ), doc='local joint axis', array_extent=('njnt', 3), ), StructFieldDecl( name='jnt_stiffness', type=PointerType( inner_type=ValueType(name='mjtNum'), ), doc='stiffness coefficient', array_extent=('njnt',), ), StructFieldDecl( name='jnt_range', type=PointerType( inner_type=ValueType(name='mjtNum'), ), doc='joint limits', array_extent=('njnt', 2), ), StructFieldDecl( name='jnt_actfrcrange', type=PointerType( inner_type=ValueType(name='mjtNum'), ), doc='range of total actuator force', array_extent=('njnt', 2), ), StructFieldDecl( name='jnt_margin', type=PointerType( inner_type=ValueType(name='mjtNum'), ), doc='min distance for limit detection', array_extent=('njnt',), ), StructFieldDecl( name='jnt_user', type=PointerType( inner_type=ValueType(name='mjtNum'), ), doc='user data', array_extent=('njnt', 'nuser_jnt'), ), StructFieldDecl( name='dof_bodyid', type=PointerType( inner_type=ValueType(name='int'), ), doc="id of dof's body", array_extent=('nv',), ), StructFieldDecl( name='dof_jntid', type=PointerType( inner_type=ValueType(name='int'), ), doc="id of dof's joint", array_extent=('nv',), ), StructFieldDecl( name='dof_parentid', type=PointerType( inner_type=ValueType(name='int'), ), doc="id of dof's parent; -1: none", array_extent=('nv',), ), StructFieldDecl( name='dof_treeid', type=PointerType( inner_type=ValueType(name='int'), ), doc="id of dof's kinematic tree", array_extent=('nv',), ), StructFieldDecl( name='dof_Madr', type=PointerType( inner_type=ValueType(name='int'), ), doc='dof address in M-diagonal', array_extent=('nv',), ), StructFieldDecl( name='dof_simplenum', type=PointerType( inner_type=ValueType(name='int'), ), doc='number of consecutive simple dofs', array_extent=('nv',), ), StructFieldDecl( name='dof_solref', type=PointerType( inner_type=ValueType(name='mjtNum'), ), doc='constraint solver reference:frictionloss (nv x mjNREF)', ), StructFieldDecl( name='dof_solimp', type=PointerType( inner_type=ValueType(name='mjtNum'), ), doc='constraint solver impedance:frictionloss (nv x mjNIMP)', ), StructFieldDecl( name='dof_frictionloss', type=PointerType( inner_type=ValueType(name='mjtNum'), ), doc='dof friction loss', array_extent=('nv',), ), StructFieldDecl( name='dof_armature', type=PointerType( inner_type=ValueType(name='mjtNum'), ), doc='dof armature inertia/mass', array_extent=('nv',), ), StructFieldDecl( name='dof_damping', type=PointerType( inner_type=ValueType(name='mjtNum'), ), doc='damping coefficient', array_extent=('nv',), ), StructFieldDecl( name='dof_invweight0', type=PointerType( inner_type=ValueType(name='mjtNum'), ), doc='diag. inverse inertia in qpos0', array_extent=('nv',), ), StructFieldDecl( name='dof_M0', type=PointerType( inner_type=ValueType(name='mjtNum'), ), doc='diag. inertia in qpos0', array_extent=('nv',), ), StructFieldDecl( name='geom_type', type=PointerType( inner_type=ValueType(name='int'), ), doc='geometric type (mjtGeom)', array_extent=('ngeom',), ), StructFieldDecl( name='geom_contype', type=PointerType( inner_type=ValueType(name='int'), ), doc='geom contact type', array_extent=('ngeom',), ), StructFieldDecl( name='geom_conaffinity', type=PointerType( inner_type=ValueType(name='int'), ), doc='geom contact affinity', array_extent=('ngeom',), ), StructFieldDecl( name='geom_condim', type=PointerType( inner_type=ValueType(name='int'), ), doc='contact dimensionality (1, 3, 4, 6)', array_extent=('ngeom',), ), StructFieldDecl( name='geom_bodyid', type=PointerType( inner_type=ValueType(name='int'), ), doc="id of geom's body", array_extent=('ngeom',), ), StructFieldDecl( name='geom_dataid', type=PointerType( inner_type=ValueType(name='int'), ), doc="id of geom's mesh/hfield; -1: none", array_extent=('ngeom',), ), StructFieldDecl( name='geom_matid', type=PointerType( inner_type=ValueType(name='int'), ), doc='material id for rendering; -1: none', array_extent=('ngeom',), ), StructFieldDecl( name='geom_group', type=PointerType( inner_type=ValueType(name='int'), ), doc='group for visibility', array_extent=('ngeom',), ), StructFieldDecl( name='geom_priority', type=PointerType( inner_type=ValueType(name='int'), ), doc='geom contact priority', array_extent=('ngeom',), ), StructFieldDecl( name='geom_plugin', type=PointerType( inner_type=ValueType(name='int'), ), doc='plugin instance id; -1: not in use', array_extent=('ngeom',), ), StructFieldDecl( name='geom_sameframe', type=PointerType( inner_type=ValueType(name='mjtByte'), ), doc='same frame as body (mjtSameframe)', array_extent=('ngeom',), ), StructFieldDecl( name='geom_solmix', type=PointerType( inner_type=ValueType(name='mjtNum'), ), doc='mixing coef for solref/imp in geom pair', array_extent=('ngeom',), ), StructFieldDecl( name='geom_solref', type=PointerType( inner_type=ValueType(name='mjtNum'), ), doc='constraint solver reference: contact', array_extent=('ngeom', 'mjNREF'), ), StructFieldDecl( name='geom_solimp', type=PointerType( inner_type=ValueType(name='mjtNum'), ), doc='constraint solver impedance: contact', array_extent=('ngeom', 'mjNIMP'), ), StructFieldDecl( name='geom_size', type=PointerType( inner_type=ValueType(name='mjtNum'), ), doc='geom-specific size parameters', array_extent=('ngeom', 3), ), StructFieldDecl( name='geom_aabb', type=PointerType( inner_type=ValueType(name='mjtNum'), ), doc='bounding box, (center, size)', array_extent=('ngeom', 6), ), StructFieldDecl( name='geom_rbound', type=PointerType( inner_type=ValueType(name='mjtNum'), ), doc='radius of bounding sphere', array_extent=('ngeom',), ), StructFieldDecl( name='geom_pos', type=PointerType( inner_type=ValueType(name='mjtNum'), ), doc='local position offset rel. to body', array_extent=('ngeom', 3), ), StructFieldDecl( name='geom_quat', type=PointerType( inner_type=ValueType(name='mjtNum'), ), doc='local orientation offset rel. to body', array_extent=('ngeom', 4), ), StructFieldDecl( name='geom_friction', type=PointerType( inner_type=ValueType(name='mjtNum'), ), doc='friction for (slide, spin, roll)', array_extent=('ngeom', 3), ), StructFieldDecl( name='geom_margin', type=PointerType( inner_type=ValueType(name='mjtNum'), ), doc='detect contact if dist