MjModel

Struct MjModel 

Source
pub struct MjModel(/* private fields */);
Expand description

A Rust-safe wrapper around mjModel. Automatically clean after itself on destruction.

Implementations§

Source§

impl MjModel

Source

pub fn from_xml<T: AsRef<Path>>(path: T) -> Result<Self, Error>

Loads the model from an XML file. To load from a virtual file system, use MjModel::from_xml_vfs.

Source

pub fn from_xml_vfs<T: AsRef<Path>>(path: T, vfs: &MjVfs) -> Result<Self, Error>

Loads the model from an XML file, located in a virtual file system (vfs).

Source

pub fn from_xml_string(data: &str) -> Result<Self, Error>

Loads the model from an XML string.

Source

pub fn from_buffer(data: &[u8]) -> Result<Self, Error>

Loads the model from MJB raw data.

Source

pub fn save_last_xml(&self, filename: &str) -> Result<()>

Saves the last XML loaded.

Source

pub fn make_data(&self) -> MjData<&Self>

Creates a new MjData instances linked to this model.

Source

pub fn actuator(&self, name: &str) -> Option<MjActuatorModelInfo>

Obtains a MjActuatorModelInfo struct containing information about the name, id, and indices required for obtaining references to the correct locations in MjModel. The actual view can be obtained via MjActuatorModelInfo::view.

§Panics

A panic will occur if name contains \0 characters.

Source

pub fn sensor(&self, name: &str) -> Option<MjSensorModelInfo>

Obtains a MjSensorModelInfo struct containing information about the name, id, and indices required for obtaining references to the correct locations in MjModel. The actual view can be obtained via MjSensorModelInfo::view.

§Panics

A panic will occur if name contains \0 characters.

Source

pub fn tendon(&self, name: &str) -> Option<MjTendonModelInfo>

Obtains a MjTendonModelInfo struct containing information about the name, id, and indices required for obtaining references to the correct locations in MjModel. The actual view can be obtained via MjTendonModelInfo::view.

§Panics

A panic will occur if name contains \0 characters.

Source

pub fn joint(&self, name: &str) -> Option<MjJointModelInfo>

Obtains a MjJointModelInfo struct containing information about the name, id, and indices required for obtaining references to the correct locations in MjModel. The actual view can be obtained via MjJointModelInfo::view.

§Panics

A panic will occur if name contains \0 characters.

Source

pub fn geom(&self, name: &str) -> Option<MjGeomModelInfo>

Obtains a MjGeomModelInfo struct containing information about the name, id, and indices required for obtaining references to the correct locations in MjModel. The actual view can be obtained via MjGeomModelInfo::view.

§Panics

A panic will occur if name contains \0 characters.

Source

pub fn body(&self, name: &str) -> Option<MjBodyModelInfo>

Obtains a MjBodyModelInfo struct containing information about the name, id, and indices required for obtaining references to the correct locations in MjModel. The actual view can be obtained via MjBodyModelInfo::view.

§Panics

A panic will occur if name contains \0 characters.

Source

pub fn camera(&self, name: &str) -> Option<MjCameraModelInfo>

Obtains a MjCameraModelInfo struct containing information about the name, id, and indices required for obtaining references to the correct locations in MjModel. The actual view can be obtained via MjCameraModelInfo::view.

§Panics

A panic will occur if name contains \0 characters.

Source

pub fn key(&self, name: &str) -> Option<MjKeyModelInfo>

Obtains a MjKeyModelInfo struct containing information about the name, id, and indices required for obtaining references to the correct locations in MjModel. The actual view can be obtained via MjKeyModelInfo::view.

§Panics

A panic will occur if name contains \0 characters.

Source

pub fn tuple(&self, name: &str) -> Option<MjTupleModelInfo>

Obtains a MjTupleModelInfo struct containing information about the name, id, and indices required for obtaining references to the correct locations in MjModel. The actual view can be obtained via MjTupleModelInfo::view.

§Panics

A panic will occur if name contains \0 characters.

Source

pub fn texture(&self, name: &str) -> Option<MjTextureModelInfo>

Obtains a MjTextureModelInfo struct containing information about the name, id, and indices required for obtaining references to the correct locations in MjModel. The actual view can be obtained via MjTextureModelInfo::view.

§Panics

A panic will occur if name contains \0 characters.

Source

pub fn site(&self, name: &str) -> Option<MjSiteModelInfo>

Obtains a MjSiteModelInfo struct containing information about the name, id, and indices required for obtaining references to the correct locations in MjModel. The actual view can be obtained via MjSiteModelInfo::view.

§Panics

A panic will occur if name contains \0 characters.

Source

pub fn pair(&self, name: &str) -> Option<MjPairModelInfo>

Obtains a MjPairModelInfo struct containing information about the name, id, and indices required for obtaining references to the correct locations in MjModel. The actual view can be obtained via MjPairModelInfo::view.

§Panics

A panic will occur if name contains \0 characters.

Source

pub fn numeric(&self, name: &str) -> Option<MjNumericModelInfo>

Obtains a MjNumericModelInfo struct containing information about the name, id, and indices required for obtaining references to the correct locations in MjModel. The actual view can be obtained via MjNumericModelInfo::view.

§Panics

A panic will occur if name contains \0 characters.

Source

pub fn material(&self, name: &str) -> Option<MjMaterialModelInfo>

Obtains a MjMaterialModelInfo struct containing information about the name, id, and indices required for obtaining references to the correct locations in MjModel. The actual view can be obtained via MjMaterialModelInfo::view.

§Panics

A panic will occur if name contains \0 characters.

Source

pub fn light(&self, name: &str) -> Option<MjLightModelInfo>

Obtains a MjLightModelInfo struct containing information about the name, id, and indices required for obtaining references to the correct locations in MjModel. The actual view can be obtained via MjLightModelInfo::view.

§Panics

A panic will occur if name contains \0 characters.

Source

pub fn equality(&self, name: &str) -> Option<MjEqualityModelInfo>

Obtains a MjEqualityModelInfo struct containing information about the name, id, and indices required for obtaining references to the correct locations in MjModel. The actual view can be obtained via MjEqualityModelInfo::view.

§Panics

A panic will occur if name contains \0 characters.

Source

pub fn hfield(&self, name: &str) -> Option<MjHfieldModelInfo>

Obtains a MjHfieldModelInfo struct containing information about the name, id, and indices required for obtaining references to the correct locations in MjModel. The actual view can be obtained via MjHfieldModelInfo::view.

§Panics

A panic will occur if name contains \0 characters.

Source

pub fn name2id(&self, type_: MjtObj, name: &str) -> i32

👎Deprecated

Deprecated alias for MjModel::name_to_id.

Source

pub fn name_to_id(&self, type_: MjtObj, name: &str) -> i32

Translates name to the correct id. Wrapper around mj_name2id.

§Panics

When the name contains ‘\0’ characters, a panic occurs.

Source

pub fn clone(&self) -> Option<MjModel>

Clones the model.

Source

pub fn save(&self, filename: Option<&str>, buffer: Option<&mut [u8]>)

Save model to binary MJB file or memory buffer; buffer has precedence when given.

§Panics

When the filename contains ‘\0’ characters, a panic occurs.

Source

pub fn size(&self) -> i32

Return size of buffer needed to hold model.

Source

pub fn print_formatted( &self, filename: &str, float_format: &str, ) -> Result<(), NulError>

Print mjModel to text file, specifying format. float_format must be a valid printf-style format string for a single float value.

Source

pub fn print(&self, filename: &str) -> Result<(), NulError>

Print model to text file.

Source

pub fn state_size(&self, spec: u32) -> i32

Return size of state specification. The bits of the integer spec correspond to element fields of MjtState.

Source

pub fn is_pyramidal(&self) -> bool

Determine type of friction cone.

Source

pub fn is_sparse(&self) -> bool

Determine type of constraint Jacobian.

Source

pub fn is_dual(&self) -> bool

Determine type of solver (PGS is dual, CG and Newton are primal).

Source

pub fn id_to_name(&self, type_: MjtObj, id: i32) -> Option<&str>

Get name of object with the specified MjtObj type and id, returns NULL if name not found. Wraps mj_id2name.

Source

pub fn get_totalmass(&self) -> MjtNum

Sum all body masses.

Source

pub fn set_totalmass(&mut self, newmass: MjtNum)

Scale body masses and inertias to achieve specified total mass.

Source

pub fn ffi(&self) -> &mjModel

Returns a reference to the wrapped FFI struct.

Source

pub unsafe fn ffi_mut(&mut self) -> &mut mjModel

Returns a mutable reference to the wrapped FFI struct.

Source§

impl MjModel

Public attribute methods.

Source

pub fn signature(&self) -> u64

Compilation signature.

Source

pub fn nq(&self) -> i32

Return value of number of generalized coordinates = dim(qpos).

Source

pub fn nv(&self) -> i32

Return value of number of degrees of freedom = dim(qvel).

Source

pub fn nu(&self) -> i32

Return value of number of actuators/controls = dim(ctrl).

Source

pub fn na(&self) -> i32

Return value of number of activation states = dim(act).

Source

pub fn nbody(&self) -> i32

Return value of number of bodies.

Source

pub fn nbvh(&self) -> i32

Return value of number of total bounding volumes in all bodies.

Source

pub fn nbvhstatic(&self) -> i32

Return value of number of static bounding volumes (aabb stored in mjModel).

Source

pub fn nbvhdynamic(&self) -> i32

Return value of number of dynamic bounding volumes (aabb stored in mjData).

Source

pub fn noct(&self) -> i32

Return value of number of total octree cells in all meshes.

Source

pub fn njnt(&self) -> i32

Return value of number of joints.

Source

pub fn ntree(&self) -> i32

Return value of number of kinematic trees under world body.

Source

pub fn n_m(&self) -> i32

Return value of number of non-zeros in sparse inertia matrix.

Source

pub fn n_b(&self) -> i32

Return value of number of non-zeros in sparse body-dof matrix.

Source

pub fn n_c(&self) -> i32

Return value of number of non-zeros in sparse reduced dof-dof matrix.

Source

pub fn n_d(&self) -> i32

Return value of number of non-zeros in sparse dof-dof matrix.

Source

pub fn ngeom(&self) -> i32

Return value of number of geoms.

Source

pub fn nsite(&self) -> i32

Return value of number of sites.

Source

pub fn ncam(&self) -> i32

Return value of number of cameras.

Source

pub fn nlight(&self) -> i32

Return value of number of lights.

Source

pub fn nflex(&self) -> i32

Return value of number of flexes.

Source

pub fn nflexnode(&self) -> i32

Return value of number of dofs in all flexes.

Source

pub fn nflexvert(&self) -> i32

Return value of number of vertices in all flexes.

Source

pub fn nflexedge(&self) -> i32

Return value of number of edges in all flexes.

Source

pub fn nflexelem(&self) -> i32

Return value of number of elements in all flexes.

Source

pub fn nflexelemdata(&self) -> i32

Return value of number of element vertex ids in all flexes.

Source

pub fn nflexelemedge(&self) -> i32

Return value of number of element edge ids in all flexes.

Source

pub fn nflexshelldata(&self) -> i32

Return value of number of shell fragment vertex ids in all flexes.

Source

pub fn nflexevpair(&self) -> i32

Return value of number of element-vertex pairs in all flexes.

Source

pub fn nflextexcoord(&self) -> i32

Return value of number of vertices with texture coordinates.

Source

pub fn nmesh(&self) -> i32

Return value of number of meshes.

Source

pub fn nmeshvert(&self) -> i32

Return value of number of vertices in all meshes.

Source

pub fn nmeshnormal(&self) -> i32

Return value of number of normals in all meshes.

Source

pub fn nmeshtexcoord(&self) -> i32

Return value of number of texcoords in all meshes.

Source

pub fn nmeshface(&self) -> i32

Return value of number of triangular faces in all meshes.

Source

pub fn nmeshgraph(&self) -> i32

Return value of number of ints in mesh auxiliary data.

Source

pub fn nmeshpoly(&self) -> i32

Return value of number of polygons in all meshes.

Source

pub fn nmeshpolyvert(&self) -> i32

Return value of number of vertices in all polygons.

Source

pub fn nmeshpolymap(&self) -> i32

Return value of number of polygons in vertex map.

Source

pub fn nskin(&self) -> i32

Return value of number of skins.

Source

pub fn nskinvert(&self) -> i32

Return value of number of vertices in all skins.

Source

pub fn nskintexvert(&self) -> i32

Return value of number of vertices with texcoords in all skins.

Source

pub fn nskinface(&self) -> i32

Return value of number of triangular faces in all skins.

Source

pub fn nskinbone(&self) -> i32

Return value of number of bones in all skins.

Source

pub fn nskinbonevert(&self) -> i32

Return value of number of vertices in all skin bones.

Source

pub fn nhfield(&self) -> i32

Return value of number of heightfields.

Source

pub fn nhfielddata(&self) -> i32

Return value of number of data points in all heightfields.

Source

pub fn ntex(&self) -> i32

Return value of number of textures.

Source

pub fn ntexdata(&self) -> i32

Return value of number of bytes in texture rgb data.

Source

pub fn nmat(&self) -> i32

Return value of number of materials.

Source

pub fn npair(&self) -> i32

Return value of number of predefined geom pairs.

Source

pub fn nexclude(&self) -> i32

Return value of number of excluded geom pairs.

Source

pub fn neq(&self) -> i32

Return value of number of equality constraints.

Source

pub fn ntendon(&self) -> i32

Return value of number of tendons.

Source

pub fn nwrap(&self) -> i32

Return value of number of wrap objects in all tendon paths.

Source

pub fn nsensor(&self) -> i32

Return value of number of sensors.

Source

pub fn nnumeric(&self) -> i32

Return value of number of numeric custom fields.

Source

pub fn nnumericdata(&self) -> i32

Return value of number of mjtNums in all numeric fields.

Source

pub fn ntext(&self) -> i32

Return value of number of text custom fields.

Source

pub fn ntextdata(&self) -> i32

Return value of number of mjtBytes in all text fields.

Source

pub fn ntuple(&self) -> i32

Return value of number of tuple custom fields.

Source

pub fn ntupledata(&self) -> i32

Return value of number of objects in all tuple fields.

Source

pub fn nkey(&self) -> i32

Return value of number of keyframes.

Source

pub fn nmocap(&self) -> i32

Return value of number of mocap bodies.

Source

pub fn nplugin(&self) -> i32

Return value of number of plugin instances.

Source

pub fn npluginattr(&self) -> i32

Return value of number of chars in all plugin config attributes.

Source

pub fn nuser_body(&self) -> i32

Return value of number of mjtNums in body_user.

Source

pub fn nuser_jnt(&self) -> i32

Return value of number of mjtNums in jnt_user.

Source

pub fn nuser_geom(&self) -> i32

Return value of number of mjtNums in geom_user.

Source

pub fn nuser_site(&self) -> i32

Return value of number of mjtNums in site_user.

Source

pub fn nuser_cam(&self) -> i32

Return value of number of mjtNums in cam_user.

Source

pub fn nuser_tendon(&self) -> i32

Return value of number of mjtNums in tendon_user.

Source

pub fn nuser_actuator(&self) -> i32

Return value of number of mjtNums in actuator_user.

Source

pub fn nuser_sensor(&self) -> i32

Return value of number of mjtNums in sensor_user.

Source

pub fn nnames(&self) -> i32

Return value of number of chars in all names.

Source

pub fn npaths(&self) -> i32

Return value of number of chars in all paths.

Source

pub fn nnames_map(&self) -> i32

Return value of number of slots in the names hash map.

Source

pub fn n_jmom(&self) -> i32

Return value of number of non-zeros in sparse actuator_moment matrix.

Source

pub fn ngravcomp(&self) -> i32

Return value of number of bodies with nonzero gravcomp.

Source

pub fn nemax(&self) -> i32

Return value of number of potential equality-constraint rows.

Source

pub fn njmax(&self) -> i32

Return value of number of available rows in constraint Jacobian (legacy).

Source

pub fn nconmax(&self) -> i32

Return value of number of potential contacts in contact list (legacy).

Source

pub fn nuserdata(&self) -> i32

Return value of number of mjtNums reserved for the user.

Source

pub fn nsensordata(&self) -> i32

Return value of number of mjtNums in sensor data vector.

Source

pub fn npluginstate(&self) -> i32

Return value of number of mjtNums in plugin state vector.

Source

pub fn narena(&self) -> MjtSize

Return value of number of bytes in the mjData arena (inclusive of stack).

Source

pub fn nbuffer(&self) -> MjtSize

Return value of number of bytes in buffer.

Source

pub fn opt(&self) -> &MjOption

Return an immutable reference to physics options.

Source

pub fn opt_mut(&mut self) -> &mut MjOption

Return a mutable reference to physics options.

Source

pub fn vis(&self) -> &MjVisual

Return an immutable reference to visualization options.

Source

pub fn vis_mut(&mut self) -> &mut MjVisual

Return a mutable reference to visualization options.

Source

pub fn stat(&self) -> &MjStatistic

Return an immutable reference to model statistics.

Source

pub fn stat_mut(&mut self) -> &mut MjStatistic

Return a mutable reference to model statistics.

Source§

impl MjModel

Array slices.

Source

pub fn qpos0(&self) -> &[MjtNum]

Immutable slice of the qpos values at default pose array.

Source

pub fn qpos0_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the qpos values at default pose array.

Source

pub fn qpos_spring(&self) -> &[MjtNum]

Immutable slice of the reference pose for springs array.

Source

pub fn qpos_spring_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the reference pose for springs array.

Source

pub fn body_parentid(&self) -> &[i32]

Immutable slice of the id of body’s parent array.

Source

pub fn body_parentid_mut(&mut self) -> &mut [i32]

Mutable slice of the id of body’s parent array.

Source

pub fn body_rootid(&self) -> &[i32]

Immutable slice of the id of root above body array.

Source

pub fn body_rootid_mut(&mut self) -> &mut [i32]

Mutable slice of the id of root above body array.

Source

pub fn body_weldid(&self) -> &[i32]

Immutable slice of the id of body that this body is welded to array.

Source

pub fn body_weldid_mut(&mut self) -> &mut [i32]

Mutable slice of the id of body that this body is welded to array.

Source

pub fn body_mocapid(&self) -> &[i32]

Immutable slice of the id of mocap data; -1: none array.

Source

pub fn body_mocapid_mut(&mut self) -> &mut [i32]

Mutable slice of the id of mocap data; -1: none array.

Source

pub fn body_jntnum(&self) -> &[i32]

Immutable slice of the number of joints for this body array.

Source

pub fn body_jntnum_mut(&mut self) -> &mut [i32]

Mutable slice of the number of joints for this body array.

Source

pub fn body_jntadr(&self) -> &[i32]

Immutable slice of the start addr of joints; -1: no joints array.

Source

pub fn body_jntadr_mut(&mut self) -> &mut [i32]

Mutable slice of the start addr of joints; -1: no joints array.

Source

pub fn body_dofnum(&self) -> &[i32]

Immutable slice of the number of motion degrees of freedom array.

Source

pub fn body_dofnum_mut(&mut self) -> &mut [i32]

Mutable slice of the number of motion degrees of freedom array.

Source

pub fn body_dofadr(&self) -> &[i32]

Immutable slice of the start addr of dofs; -1: no dofs array.

Source

pub fn body_dofadr_mut(&mut self) -> &mut [i32]

Mutable slice of the start addr of dofs; -1: no dofs array.

Source

pub fn body_treeid(&self) -> &[i32]

Immutable slice of the id of body’s kinematic tree; -1: static array.

Source

pub fn body_treeid_mut(&mut self) -> &mut [i32]

Mutable slice of the id of body’s kinematic tree; -1: static array.

Source

pub fn body_geomnum(&self) -> &[i32]

Immutable slice of the number of geoms array.

Source

pub fn body_geomnum_mut(&mut self) -> &mut [i32]

Mutable slice of the number of geoms array.

Source

pub fn body_geomadr(&self) -> &[i32]

Immutable slice of the start addr of geoms; -1: no geoms array.

Source

pub fn body_geomadr_mut(&mut self) -> &mut [i32]

Mutable slice of the start addr of geoms; -1: no geoms array.

Source

pub fn body_simple(&self) -> &[MjtByte]

Immutable slice of the 1: diag M; 2: diag M, sliders only array.

Source

pub fn body_simple_mut(&mut self) -> &mut [MjtByte]

Mutable slice of the 1: diag M; 2: diag M, sliders only array.

Source

pub fn body_sameframe(&self) -> &[MjtSameFrame]

Immutable slice of the same frame as inertia array.

Source

pub fn body_sameframe_mut(&mut self) -> &mut [MjtSameFrame]

Mutable slice of the same frame as inertia array.

Source

pub fn body_pos(&self) -> &[[MjtNum; 3]]

Immutable slice of the position offset rel. to parent body array.

Source

pub fn body_pos_mut(&mut self) -> &mut [[MjtNum; 3]]

Mutable slice of the position offset rel. to parent body array.

Source

pub fn body_quat(&self) -> &[[MjtNum; 4]]

Immutable slice of the orientation offset rel. to parent body array.

Source

pub fn body_quat_mut(&mut self) -> &mut [[MjtNum; 4]]

Mutable slice of the orientation offset rel. to parent body array.

Source

pub fn body_ipos(&self) -> &[[MjtNum; 3]]

Immutable slice of the local position of center of mass array.

Source

pub fn body_ipos_mut(&mut self) -> &mut [[MjtNum; 3]]

Mutable slice of the local position of center of mass array.

Source

pub fn body_iquat(&self) -> &[[MjtNum; 4]]

Immutable slice of the local orientation of inertia ellipsoid array.

Source

pub fn body_iquat_mut(&mut self) -> &mut [[MjtNum; 4]]

Mutable slice of the local orientation of inertia ellipsoid array.

Source

pub fn body_mass(&self) -> &[MjtNum]

Immutable slice of the mass array.

Source

pub fn body_mass_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the mass array.

Source

pub fn body_subtreemass(&self) -> &[MjtNum]

Immutable slice of the mass of subtree starting at this body array.

Source

pub fn body_subtreemass_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the mass of subtree starting at this body array.

Source

pub fn body_inertia(&self) -> &[[MjtNum; 3]]

Immutable slice of the diagonal inertia in ipos/iquat frame array.

Source

pub fn body_inertia_mut(&mut self) -> &mut [[MjtNum; 3]]

Mutable slice of the diagonal inertia in ipos/iquat frame array.

Source

pub fn body_invweight0(&self) -> &[[MjtNum; 2]]

Immutable slice of the mean inv inert in qpos0 (trn, rot) array.

Source

pub fn body_invweight0_mut(&mut self) -> &mut [[MjtNum; 2]]

Mutable slice of the mean inv inert in qpos0 (trn, rot) array.

Source

pub fn body_gravcomp(&self) -> &[MjtNum]

Immutable slice of the antigravity force, units of body weight array.

Source

pub fn body_gravcomp_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the antigravity force, units of body weight array.

Source

pub fn body_margin(&self) -> &[MjtNum]

Immutable slice of the MAX over all geom margins array.

Source

pub fn body_margin_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the MAX over all geom margins array.

Source

pub fn body_plugin(&self) -> &[i32]

Immutable slice of the plugin instance id; -1: not in use array.

Source

pub fn body_plugin_mut(&mut self) -> &mut [i32]

Mutable slice of the plugin instance id; -1: not in use array.

Source

pub fn body_contype(&self) -> &[i32]

Immutable slice of the OR over all geom contypes array.

Source

pub fn body_contype_mut(&mut self) -> &mut [i32]

Mutable slice of the OR over all geom contypes array.

Source

pub fn body_conaffinity(&self) -> &[i32]

Immutable slice of the OR over all geom conaffinities array.

Source

pub fn body_conaffinity_mut(&mut self) -> &mut [i32]

Mutable slice of the OR over all geom conaffinities array.

Source

pub fn body_bvhadr(&self) -> &[i32]

Immutable slice of the address of bvh root array.

Source

pub fn body_bvhadr_mut(&mut self) -> &mut [i32]

Mutable slice of the address of bvh root array.

Source

pub fn body_bvhnum(&self) -> &[i32]

Immutable slice of the number of bounding volumes array.

Source

pub fn body_bvhnum_mut(&mut self) -> &mut [i32]

Mutable slice of the number of bounding volumes array.

Source

pub fn bvh_depth(&self) -> &[i32]

Immutable slice of the depth in the bounding volume hierarchy array.

Source

pub fn bvh_depth_mut(&mut self) -> &mut [i32]

Mutable slice of the depth in the bounding volume hierarchy array.

Source

pub fn bvh_child(&self) -> &[[i32; 2]]

Immutable slice of the left and right children in tree array.

Source

pub fn bvh_child_mut(&mut self) -> &mut [[i32; 2]]

Mutable slice of the left and right children in tree array.

Source

pub fn bvh_nodeid(&self) -> &[i32]

Immutable slice of the geom or elem id of node; -1: non-leaf array.

Source

pub fn bvh_nodeid_mut(&mut self) -> &mut [i32]

Mutable slice of the geom or elem id of node; -1: non-leaf array.

Source

pub fn bvh_aabb(&self) -> &[[MjtNum; 6]]

Immutable slice of the local bounding box (center, size) array.

Source

pub fn bvh_aabb_mut(&mut self) -> &mut [[MjtNum; 6]]

Mutable slice of the local bounding box (center, size) array.

Source

pub fn oct_depth(&self) -> &[i32]

Immutable slice of the depth in the octree array.

Source

pub fn oct_depth_mut(&mut self) -> &mut [i32]

Mutable slice of the depth in the octree array.

Source

pub fn oct_child(&self) -> &[[i32; 8]]

Immutable slice of the children of octree node array.

Source

pub fn oct_child_mut(&mut self) -> &mut [[i32; 8]]

Mutable slice of the children of octree node array.

Source

pub fn oct_aabb(&self) -> &[[MjtNum; 6]]

Immutable slice of the octree node bounding box (center, size) array.

Source

pub fn oct_aabb_mut(&mut self) -> &mut [[MjtNum; 6]]

Mutable slice of the octree node bounding box (center, size) array.

Source

pub fn oct_coeff(&self) -> &[[MjtNum; 8]]

Immutable slice of the octree interpolation coefficients array.

Source

pub fn oct_coeff_mut(&mut self) -> &mut [[MjtNum; 8]]

Mutable slice of the octree interpolation coefficients array.

Source

pub fn jnt_type(&self) -> &[MjtJoint]

Immutable slice of the type of joint array.

Source

pub fn jnt_type_mut(&mut self) -> &mut [MjtJoint]

Mutable slice of the type of joint array.

Source

pub fn jnt_qposadr(&self) -> &[i32]

Immutable slice of the start addr in ‘qpos’ for joint’s data array.

Source

pub fn jnt_qposadr_mut(&mut self) -> &mut [i32]

Mutable slice of the start addr in ‘qpos’ for joint’s data array.

Source

pub fn jnt_dofadr(&self) -> &[i32]

Immutable slice of the start addr in ‘qvel’ for joint’s data array.

Source

pub fn jnt_dofadr_mut(&mut self) -> &mut [i32]

Mutable slice of the start addr in ‘qvel’ for joint’s data array.

Source

pub fn jnt_bodyid(&self) -> &[i32]

Immutable slice of the id of joint’s body array.

Source

pub fn jnt_bodyid_mut(&mut self) -> &mut [i32]

Mutable slice of the id of joint’s body array.

Source

pub fn jnt_group(&self) -> &[i32]

Immutable slice of the group for visibility array.

Source

pub fn jnt_group_mut(&mut self) -> &mut [i32]

Mutable slice of the group for visibility array.

Source

pub fn jnt_limited(&self) -> &[bool]

Immutable slice of the does joint have limits array.

Source

pub fn jnt_limited_mut(&mut self) -> &mut [bool]

Mutable slice of the does joint have limits array.

Source

pub fn jnt_actfrclimited(&self) -> &[bool]

Immutable slice of the does joint have actuator force limits array.

Source

pub fn jnt_actfrclimited_mut(&mut self) -> &mut [bool]

Mutable slice of the does joint have actuator force limits array.

Source

pub fn jnt_actgravcomp(&self) -> &[bool]

Immutable slice of the is gravcomp force applied via actuators array.

Source

pub fn jnt_actgravcomp_mut(&mut self) -> &mut [bool]

Mutable slice of the is gravcomp force applied via actuators array.

Source

pub fn jnt_solref(&self) -> &[[MjtNum; 2]]

Immutable slice of the constraint solver reference: limit array.

Source

pub fn jnt_solref_mut(&mut self) -> &mut [[MjtNum; 2]]

Mutable slice of the constraint solver reference: limit array.

Source

pub fn jnt_solimp(&self) -> &[[MjtNum; 5]]

Immutable slice of the constraint solver impedance: limit array.

Source

pub fn jnt_solimp_mut(&mut self) -> &mut [[MjtNum; 5]]

Mutable slice of the constraint solver impedance: limit array.

Source

pub fn jnt_pos(&self) -> &[[MjtNum; 3]]

Immutable slice of the local anchor position array.

Source

pub fn jnt_pos_mut(&mut self) -> &mut [[MjtNum; 3]]

Mutable slice of the local anchor position array.

Source

pub fn jnt_axis(&self) -> &[[MjtNum; 3]]

Immutable slice of the local joint axis array.

Source

pub fn jnt_axis_mut(&mut self) -> &mut [[MjtNum; 3]]

Mutable slice of the local joint axis array.

Source

pub fn jnt_stiffness(&self) -> &[MjtNum]

Immutable slice of the stiffness coefficient array.

Source

pub fn jnt_stiffness_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the stiffness coefficient array.

Source

pub fn jnt_range(&self) -> &[[MjtNum; 2]]

Immutable slice of the joint limits array.

Source

pub fn jnt_range_mut(&mut self) -> &mut [[MjtNum; 2]]

Mutable slice of the joint limits array.

Source

pub fn jnt_actfrcrange(&self) -> &[[MjtNum; 2]]

Immutable slice of the range of total actuator force array.

Source

pub fn jnt_actfrcrange_mut(&mut self) -> &mut [[MjtNum; 2]]

Mutable slice of the range of total actuator force array.

Source

pub fn jnt_margin(&self) -> &[MjtNum]

Immutable slice of the min distance for limit detection array.

Source

pub fn jnt_margin_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the min distance for limit detection array.

Source

pub fn dof_bodyid(&self) -> &[i32]

Immutable slice of the id of dof’s body array.

Source

pub fn dof_bodyid_mut(&mut self) -> &mut [i32]

Mutable slice of the id of dof’s body array.

Source

pub fn dof_jntid(&self) -> &[i32]

Immutable slice of the id of dof’s joint array.

Source

pub fn dof_jntid_mut(&mut self) -> &mut [i32]

Mutable slice of the id of dof’s joint array.

Source

pub fn dof_parentid(&self) -> &[i32]

Immutable slice of the id of dof’s parent; -1: none array.

Source

pub fn dof_parentid_mut(&mut self) -> &mut [i32]

Mutable slice of the id of dof’s parent; -1: none array.

Source

pub fn dof_treeid(&self) -> &[i32]

Immutable slice of the id of dof’s kinematic tree array.

Source

pub fn dof_treeid_mut(&mut self) -> &mut [i32]

Mutable slice of the id of dof’s kinematic tree array.

Source

pub fn dof_madr(&self) -> &[i32]

Immutable slice of the dof address in M-diagonal array.

Source

pub fn dof_madr_mut(&mut self) -> &mut [i32]

Mutable slice of the dof address in M-diagonal array.

Source

pub fn dof_simplenum(&self) -> &[i32]

Immutable slice of the number of consecutive simple dofs array.

Source

pub fn dof_simplenum_mut(&mut self) -> &mut [i32]

Mutable slice of the number of consecutive simple dofs array.

Source

pub fn dof_solref(&self) -> &[[MjtNum; 2]]

Immutable slice of the constraint solver reference:frictionloss array.

Source

pub fn dof_solref_mut(&mut self) -> &mut [[MjtNum; 2]]

Mutable slice of the constraint solver reference:frictionloss array.

Source

pub fn dof_solimp(&self) -> &[[MjtNum; 5]]

Immutable slice of the constraint solver impedance:frictionloss array.

Source

pub fn dof_solimp_mut(&mut self) -> &mut [[MjtNum; 5]]

Mutable slice of the constraint solver impedance:frictionloss array.

Source

pub fn dof_frictionloss(&self) -> &[MjtNum]

Immutable slice of the dof friction loss array.

Source

pub fn dof_frictionloss_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the dof friction loss array.

Source

pub fn dof_armature(&self) -> &[MjtNum]

Immutable slice of the dof armature inertia/mass array.

Source

pub fn dof_armature_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the dof armature inertia/mass array.

Source

pub fn dof_damping(&self) -> &[MjtNum]

Immutable slice of the damping coefficient array.

Source

pub fn dof_damping_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the damping coefficient array.

Source

pub fn dof_invweight0(&self) -> &[MjtNum]

Immutable slice of the diag. inverse inertia in qpos0 array.

Source

pub fn dof_invweight0_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the diag. inverse inertia in qpos0 array.

Source

pub fn dof_m0(&self) -> &[MjtNum]

Immutable slice of the diag. inertia in qpos0 array.

Source

pub fn dof_m0_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the diag. inertia in qpos0 array.

Source

pub fn geom_type(&self) -> &[MjtGeom]

Immutable slice of the geometric type array.

Source

pub fn geom_type_mut(&mut self) -> &mut [MjtGeom]

Mutable slice of the geometric type array.

Source

pub fn geom_contype(&self) -> &[i32]

Immutable slice of the geom contact type array.

Source

pub fn geom_contype_mut(&mut self) -> &mut [i32]

Mutable slice of the geom contact type array.

Source

pub fn geom_conaffinity(&self) -> &[i32]

Immutable slice of the geom contact affinity array.

Source

pub fn geom_conaffinity_mut(&mut self) -> &mut [i32]

Mutable slice of the geom contact affinity array.

Source

pub fn geom_condim(&self) -> &[i32]

Immutable slice of the contact dimensionality (1, 3, 4, 6) array.

Source

pub fn geom_condim_mut(&mut self) -> &mut [i32]

Mutable slice of the contact dimensionality (1, 3, 4, 6) array.

Source

pub fn geom_bodyid(&self) -> &[i32]

Immutable slice of the id of geom’s body array.

Source

pub fn geom_bodyid_mut(&mut self) -> &mut [i32]

Mutable slice of the id of geom’s body array.

Source

pub fn geom_dataid(&self) -> &[i32]

Immutable slice of the id of geom’s mesh/hfield; -1: none array.

Source

pub fn geom_dataid_mut(&mut self) -> &mut [i32]

Mutable slice of the id of geom’s mesh/hfield; -1: none array.

Source

pub fn geom_matid(&self) -> &[i32]

Immutable slice of the material id for rendering; -1: none array.

Source

pub fn geom_matid_mut(&mut self) -> &mut [i32]

Mutable slice of the material id for rendering; -1: none array.

Source

pub fn geom_group(&self) -> &[i32]

Immutable slice of the group for visibility array.

Source

pub fn geom_group_mut(&mut self) -> &mut [i32]

Mutable slice of the group for visibility array.

Source

pub fn geom_priority(&self) -> &[i32]

Immutable slice of the geom contact priority array.

Source

pub fn geom_priority_mut(&mut self) -> &mut [i32]

Mutable slice of the geom contact priority array.

Source

pub fn geom_plugin(&self) -> &[i32]

Immutable slice of the plugin instance id; -1: not in use array.

Source

pub fn geom_plugin_mut(&mut self) -> &mut [i32]

Mutable slice of the plugin instance id; -1: not in use array.

Source

pub fn geom_sameframe(&self) -> &[MjtSameFrame]

Immutable slice of the same frame as body array.

Source

pub fn geom_sameframe_mut(&mut self) -> &mut [MjtSameFrame]

Mutable slice of the same frame as body array.

Source

pub fn geom_solmix(&self) -> &[MjtNum]

Immutable slice of the mixing coef for solref/imp in geom pair array.

Source

pub fn geom_solmix_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the mixing coef for solref/imp in geom pair array.

Source

pub fn geom_solref(&self) -> &[[MjtNum; 2]]

Immutable slice of the constraint solver reference: contact array.

Source

pub fn geom_solref_mut(&mut self) -> &mut [[MjtNum; 2]]

Mutable slice of the constraint solver reference: contact array.

Source

pub fn geom_solimp(&self) -> &[[MjtNum; 5]]

Immutable slice of the constraint solver impedance: contact array.

Source

pub fn geom_solimp_mut(&mut self) -> &mut [[MjtNum; 5]]

Mutable slice of the constraint solver impedance: contact array.

Source

pub fn geom_size(&self) -> &[[MjtNum; 3]]

Immutable slice of the geom-specific size parameters array.

Source

pub fn geom_size_mut(&mut self) -> &mut [[MjtNum; 3]]

Mutable slice of the geom-specific size parameters array.

Source

pub fn geom_aabb(&self) -> &[[MjtNum; 6]]

Immutable slice of the bounding box, (center, size) array.

Source

pub fn geom_aabb_mut(&mut self) -> &mut [[MjtNum; 6]]

Mutable slice of the bounding box, (center, size) array.

Source

pub fn geom_rbound(&self) -> &[MjtNum]

Immutable slice of the radius of bounding sphere array.

Source

pub fn geom_rbound_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the radius of bounding sphere array.

Source

pub fn geom_pos(&self) -> &[[MjtNum; 3]]

Immutable slice of the local position offset rel. to body array.

Source

pub fn geom_pos_mut(&mut self) -> &mut [[MjtNum; 3]]

Mutable slice of the local position offset rel. to body array.

Source

pub fn geom_quat(&self) -> &[[MjtNum; 4]]

Immutable slice of the local orientation offset rel. to body array.

Source

pub fn geom_quat_mut(&mut self) -> &mut [[MjtNum; 4]]

Mutable slice of the local orientation offset rel. to body array.

Source

pub fn geom_friction(&self) -> &[[MjtNum; 3]]

Immutable slice of the friction for (slide, spin, roll) array.

Source

pub fn geom_friction_mut(&mut self) -> &mut [[MjtNum; 3]]

Mutable slice of the friction for (slide, spin, roll) array.

Source

pub fn geom_margin(&self) -> &[MjtNum]

Immutable slice of the detect contact if dist<margin array.

Source

pub fn geom_margin_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the detect contact if dist<margin array.

Source

pub fn geom_gap(&self) -> &[MjtNum]

Immutable slice of the include in solver if dist<margin-gap array.

Source

pub fn geom_gap_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the include in solver if dist<margin-gap array.

Source

pub fn geom_fluid(&self) -> &[[MjtNum; 12]]

Immutable slice of the fluid interaction parameters array.

Source

pub fn geom_fluid_mut(&mut self) -> &mut [[MjtNum; 12]]

Mutable slice of the fluid interaction parameters array.

Source

pub fn geom_rgba(&self) -> &[[f32; 4]]

Immutable slice of the rgba when material is omitted array.

Source

pub fn geom_rgba_mut(&mut self) -> &mut [[f32; 4]]

Mutable slice of the rgba when material is omitted array.

Source

pub fn site_type(&self) -> &[MjtGeom]

Immutable slice of the geom type for rendering array.

Source

pub fn site_type_mut(&mut self) -> &mut [MjtGeom]

Mutable slice of the geom type for rendering array.

Source

pub fn site_bodyid(&self) -> &[i32]

Immutable slice of the id of site’s body array.

Source

pub fn site_bodyid_mut(&mut self) -> &mut [i32]

Mutable slice of the id of site’s body array.

Source

pub fn site_matid(&self) -> &[i32]

Immutable slice of the material id for rendering; -1: none array.

Source

pub fn site_matid_mut(&mut self) -> &mut [i32]

Mutable slice of the material id for rendering; -1: none array.

Source

pub fn site_group(&self) -> &[i32]

Immutable slice of the group for visibility array.

Source

pub fn site_group_mut(&mut self) -> &mut [i32]

Mutable slice of the group for visibility array.

Source

pub fn site_sameframe(&self) -> &[MjtSameFrame]

Immutable slice of the same frame as body array.

Source

pub fn site_sameframe_mut(&mut self) -> &mut [MjtSameFrame]

Mutable slice of the same frame as body array.

Source

pub fn site_size(&self) -> &[[MjtNum; 3]]

Immutable slice of the geom size for rendering array.

Source

pub fn site_size_mut(&mut self) -> &mut [[MjtNum; 3]]

Mutable slice of the geom size for rendering array.

Source

pub fn site_pos(&self) -> &[[MjtNum; 3]]

Immutable slice of the local position offset rel. to body array.

Source

pub fn site_pos_mut(&mut self) -> &mut [[MjtNum; 3]]

Mutable slice of the local position offset rel. to body array.

Source

pub fn site_quat(&self) -> &[[MjtNum; 4]]

Immutable slice of the local orientation offset rel. to body array.

Source

pub fn site_quat_mut(&mut self) -> &mut [[MjtNum; 4]]

Mutable slice of the local orientation offset rel. to body array.

Source

pub fn site_rgba(&self) -> &[[f32; 4]]

Immutable slice of the rgba when material is omitted array.

Source

pub fn site_rgba_mut(&mut self) -> &mut [[f32; 4]]

Mutable slice of the rgba when material is omitted array.

Source

pub fn cam_mode(&self) -> &[MjtCamLight]

Immutable slice of the camera tracking mode array.

Source

pub fn cam_mode_mut(&mut self) -> &mut [MjtCamLight]

Mutable slice of the camera tracking mode array.

Source

pub fn cam_bodyid(&self) -> &[i32]

Immutable slice of the id of camera’s body array.

Source

pub fn cam_bodyid_mut(&mut self) -> &mut [i32]

Mutable slice of the id of camera’s body array.

Source

pub fn cam_targetbodyid(&self) -> &[i32]

Immutable slice of the id of targeted body; -1: none array.

Source

pub fn cam_targetbodyid_mut(&mut self) -> &mut [i32]

Mutable slice of the id of targeted body; -1: none array.

Source

pub fn cam_pos(&self) -> &[[MjtNum; 3]]

Immutable slice of the position rel. to body frame array.

Source

pub fn cam_pos_mut(&mut self) -> &mut [[MjtNum; 3]]

Mutable slice of the position rel. to body frame array.

Source

pub fn cam_quat(&self) -> &[[MjtNum; 4]]

Immutable slice of the orientation rel. to body frame array.

Source

pub fn cam_quat_mut(&mut self) -> &mut [[MjtNum; 4]]

Mutable slice of the orientation rel. to body frame array.

Source

pub fn cam_poscom0(&self) -> &[[MjtNum; 3]]

Immutable slice of the global position rel. to sub-com in qpos0 array.

Source

pub fn cam_poscom0_mut(&mut self) -> &mut [[MjtNum; 3]]

Mutable slice of the global position rel. to sub-com in qpos0 array.

Source

pub fn cam_pos0(&self) -> &[[MjtNum; 3]]

Immutable slice of the global position rel. to body in qpos0 array.

Source

pub fn cam_pos0_mut(&mut self) -> &mut [[MjtNum; 3]]

Mutable slice of the global position rel. to body in qpos0 array.

Source

pub fn cam_mat0(&self) -> &[[MjtNum; 9]]

Immutable slice of the global orientation in qpos0 array.

Source

pub fn cam_mat0_mut(&mut self) -> &mut [[MjtNum; 9]]

Mutable slice of the global orientation in qpos0 array.

Source

pub fn cam_orthographic(&self) -> &[i32]

Immutable slice of the orthographic camera; 0: no, 1: yes array.

Source

pub fn cam_orthographic_mut(&mut self) -> &mut [i32]

Mutable slice of the orthographic camera; 0: no, 1: yes array.

Source

pub fn cam_fovy(&self) -> &[MjtNum]

Immutable slice of the y field-of-view (ortho ? len : deg) array.

Source

pub fn cam_fovy_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the y field-of-view (ortho ? len : deg) array.

Source

pub fn cam_ipd(&self) -> &[MjtNum]

Immutable slice of the inter-pupilary distance array.

Source

pub fn cam_ipd_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the inter-pupilary distance array.

Source

pub fn cam_resolution(&self) -> &[[i32; 2]]

Immutable slice of the resolution: pixels [width, height] array.

Source

pub fn cam_resolution_mut(&mut self) -> &mut [[i32; 2]]

Mutable slice of the resolution: pixels [width, height] array.

Source

pub fn cam_sensorsize(&self) -> &[[f32; 2]]

Immutable slice of the sensor size: length [width, height] array.

Source

pub fn cam_sensorsize_mut(&mut self) -> &mut [[f32; 2]]

Mutable slice of the sensor size: length [width, height] array.

Source

pub fn cam_intrinsic(&self) -> &[[f32; 4]]

Immutable slice of the [focal length; principal point] array.

Source

pub fn cam_intrinsic_mut(&mut self) -> &mut [[f32; 4]]

Mutable slice of the [focal length; principal point] array.

Source

pub fn light_mode(&self) -> &[MjtCamLight]

Immutable slice of the light tracking mode array.

Source

pub fn light_mode_mut(&mut self) -> &mut [MjtCamLight]

Mutable slice of the light tracking mode array.

Source

pub fn light_bodyid(&self) -> &[i32]

Immutable slice of the id of light’s body array.

Source

pub fn light_bodyid_mut(&mut self) -> &mut [i32]

Mutable slice of the id of light’s body array.

Source

pub fn light_targetbodyid(&self) -> &[i32]

Immutable slice of the id of targeted body; -1: none array.

Source

pub fn light_targetbodyid_mut(&mut self) -> &mut [i32]

Mutable slice of the id of targeted body; -1: none array.

Source

pub fn light_type(&self) -> &[MjtLightType]

Immutable slice of the spot, directional, etc. array.

Source

pub fn light_type_mut(&mut self) -> &mut [MjtLightType]

Mutable slice of the spot, directional, etc. array.

Source

pub fn light_texid(&self) -> &[i32]

Immutable slice of the texture id for image lights array.

Source

pub fn light_texid_mut(&mut self) -> &mut [i32]

Mutable slice of the texture id for image lights array.

Source

pub fn light_castshadow(&self) -> &[bool]

Immutable slice of the does light cast shadows array.

Source

pub fn light_castshadow_mut(&mut self) -> &mut [bool]

Mutable slice of the does light cast shadows array.

Source

pub fn light_bulbradius(&self) -> &[f32]

Immutable slice of the light radius for soft shadows array.

Source

pub fn light_bulbradius_mut(&mut self) -> &mut [f32]

Mutable slice of the light radius for soft shadows array.

Source

pub fn light_intensity(&self) -> &[f32]

Immutable slice of the intensity, in candela array.

Source

pub fn light_intensity_mut(&mut self) -> &mut [f32]

Mutable slice of the intensity, in candela array.

Source

pub fn light_range(&self) -> &[f32]

Immutable slice of the range of effectiveness array.

Source

pub fn light_range_mut(&mut self) -> &mut [f32]

Mutable slice of the range of effectiveness array.

Source

pub fn light_active(&self) -> &[bool]

Immutable slice of the is light on array.

Source

pub fn light_active_mut(&mut self) -> &mut [bool]

Mutable slice of the is light on array.

Source

pub fn light_pos(&self) -> &[[MjtNum; 3]]

Immutable slice of the position rel. to body frame array.

Source

pub fn light_pos_mut(&mut self) -> &mut [[MjtNum; 3]]

Mutable slice of the position rel. to body frame array.

Source

pub fn light_dir(&self) -> &[[MjtNum; 3]]

Immutable slice of the direction rel. to body frame array.

Source

pub fn light_dir_mut(&mut self) -> &mut [[MjtNum; 3]]

Mutable slice of the direction rel. to body frame array.

Source

pub fn light_poscom0(&self) -> &[[MjtNum; 3]]

Immutable slice of the global position rel. to sub-com in qpos0 array.

Source

pub fn light_poscom0_mut(&mut self) -> &mut [[MjtNum; 3]]

Mutable slice of the global position rel. to sub-com in qpos0 array.

Source

pub fn light_pos0(&self) -> &[[MjtNum; 3]]

Immutable slice of the global position rel. to body in qpos0 array.

Source

pub fn light_pos0_mut(&mut self) -> &mut [[MjtNum; 3]]

Mutable slice of the global position rel. to body in qpos0 array.

Source

pub fn light_dir0(&self) -> &[[MjtNum; 3]]

Immutable slice of the global direction in qpos0 array.

Source

pub fn light_dir0_mut(&mut self) -> &mut [[MjtNum; 3]]

Mutable slice of the global direction in qpos0 array.

Source

pub fn light_attenuation(&self) -> &[[f32; 3]]

Immutable slice of the OpenGL attenuation (quadratic model) array.

Source

pub fn light_attenuation_mut(&mut self) -> &mut [[f32; 3]]

Mutable slice of the OpenGL attenuation (quadratic model) array.

Source

pub fn light_cutoff(&self) -> &[f32]

Immutable slice of the OpenGL cutoff array.

Source

pub fn light_cutoff_mut(&mut self) -> &mut [f32]

Mutable slice of the OpenGL cutoff array.

Source

pub fn light_exponent(&self) -> &[f32]

Immutable slice of the OpenGL exponent array.

Source

pub fn light_exponent_mut(&mut self) -> &mut [f32]

Mutable slice of the OpenGL exponent array.

Source

pub fn light_ambient(&self) -> &[[f32; 3]]

Immutable slice of the ambient rgb (alpha=1) array.

Source

pub fn light_ambient_mut(&mut self) -> &mut [[f32; 3]]

Mutable slice of the ambient rgb (alpha=1) array.

Source

pub fn light_diffuse(&self) -> &[[f32; 3]]

Immutable slice of the diffuse rgb (alpha=1) array.

Source

pub fn light_diffuse_mut(&mut self) -> &mut [[f32; 3]]

Mutable slice of the diffuse rgb (alpha=1) array.

Source

pub fn light_specular(&self) -> &[[f32; 3]]

Immutable slice of the specular rgb (alpha=1) array.

Source

pub fn light_specular_mut(&mut self) -> &mut [[f32; 3]]

Mutable slice of the specular rgb (alpha=1) array.

Source

pub fn flex_contype(&self) -> &[i32]

Immutable slice of the flex contact type array.

Source

pub fn flex_contype_mut(&mut self) -> &mut [i32]

Mutable slice of the flex contact type array.

Source

pub fn flex_conaffinity(&self) -> &[i32]

Immutable slice of the flex contact affinity array.

Source

pub fn flex_conaffinity_mut(&mut self) -> &mut [i32]

Mutable slice of the flex contact affinity array.

Source

pub fn flex_condim(&self) -> &[i32]

Immutable slice of the contact dimensionality (1, 3, 4, 6) array.

Source

pub fn flex_condim_mut(&mut self) -> &mut [i32]

Mutable slice of the contact dimensionality (1, 3, 4, 6) array.

Source

pub fn flex_priority(&self) -> &[i32]

Immutable slice of the flex contact priority array.

Source

pub fn flex_priority_mut(&mut self) -> &mut [i32]

Mutable slice of the flex contact priority array.

Source

pub fn flex_solmix(&self) -> &[MjtNum]

Immutable slice of the mix coef for solref/imp in contact pair array.

Source

pub fn flex_solmix_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the mix coef for solref/imp in contact pair array.

Source

pub fn flex_solref(&self) -> &[[MjtNum; 2]]

Immutable slice of the constraint solver reference: contact array.

Source

pub fn flex_solref_mut(&mut self) -> &mut [[MjtNum; 2]]

Mutable slice of the constraint solver reference: contact array.

Source

pub fn flex_solimp(&self) -> &[[MjtNum; 5]]

Immutable slice of the constraint solver impedance: contact array.

Source

pub fn flex_solimp_mut(&mut self) -> &mut [[MjtNum; 5]]

Mutable slice of the constraint solver impedance: contact array.

Source

pub fn flex_friction(&self) -> &[[MjtNum; 3]]

Immutable slice of the friction for (slide, spin, roll) array.

Source

pub fn flex_friction_mut(&mut self) -> &mut [[MjtNum; 3]]

Mutable slice of the friction for (slide, spin, roll) array.

Source

pub fn flex_margin(&self) -> &[MjtNum]

Immutable slice of the detect contact if dist<margin array.

Source

pub fn flex_margin_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the detect contact if dist<margin array.

Source

pub fn flex_gap(&self) -> &[MjtNum]

Immutable slice of the include in solver if dist<margin-gap array.

Source

pub fn flex_gap_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the include in solver if dist<margin-gap array.

Source

pub fn flex_internal(&self) -> &[bool]

Immutable slice of the internal flex collision enabled array.

Source

pub fn flex_internal_mut(&mut self) -> &mut [bool]

Mutable slice of the internal flex collision enabled array.

Source

pub fn flex_selfcollide(&self) -> &[MjtFlexSelf]

Immutable slice of the self collision mode array.

Source

pub fn flex_selfcollide_mut(&mut self) -> &mut [MjtFlexSelf]

Mutable slice of the self collision mode array.

Source

pub fn flex_activelayers(&self) -> &[i32]

Immutable slice of the number of active element layers, 3D only array.

Source

pub fn flex_activelayers_mut(&mut self) -> &mut [i32]

Mutable slice of the number of active element layers, 3D only array.

Source

pub fn flex_passive(&self) -> &[i32]

Immutable slice of the passive collisions enabled array.

Source

pub fn flex_passive_mut(&mut self) -> &mut [i32]

Mutable slice of the passive collisions enabled array.

Source

pub fn flex_dim(&self) -> &[i32]

Immutable slice of the 1: lines, 2: triangles, 3: tetrahedra array.

Source

pub fn flex_dim_mut(&mut self) -> &mut [i32]

Mutable slice of the 1: lines, 2: triangles, 3: tetrahedra array.

Source

pub fn flex_matid(&self) -> &[i32]

Immutable slice of the material id for rendering array.

Source

pub fn flex_matid_mut(&mut self) -> &mut [i32]

Mutable slice of the material id for rendering array.

Source

pub fn flex_group(&self) -> &[i32]

Immutable slice of the group for visibility array.

Source

pub fn flex_group_mut(&mut self) -> &mut [i32]

Mutable slice of the group for visibility array.

Source

pub fn flex_interp(&self) -> &[i32]

Immutable slice of the interpolation (0: vertex, 1: nodes) array.

Source

pub fn flex_interp_mut(&mut self) -> &mut [i32]

Mutable slice of the interpolation (0: vertex, 1: nodes) array.

Source

pub fn flex_nodeadr(&self) -> &[i32]

Immutable slice of the first node address array.

Source

pub fn flex_nodeadr_mut(&mut self) -> &mut [i32]

Mutable slice of the first node address array.

Source

pub fn flex_nodenum(&self) -> &[i32]

Immutable slice of the number of nodes array.

Source

pub fn flex_nodenum_mut(&mut self) -> &mut [i32]

Mutable slice of the number of nodes array.

Source

pub fn flex_vertadr(&self) -> &[i32]

Immutable slice of the first vertex address array.

Source

pub fn flex_vertadr_mut(&mut self) -> &mut [i32]

Mutable slice of the first vertex address array.

Source

pub fn flex_vertnum(&self) -> &[i32]

Immutable slice of the number of vertices array.

Source

pub fn flex_vertnum_mut(&mut self) -> &mut [i32]

Mutable slice of the number of vertices array.

Source

pub fn flex_edgeadr(&self) -> &[i32]

Immutable slice of the first edge address array.

Source

pub fn flex_edgeadr_mut(&mut self) -> &mut [i32]

Mutable slice of the first edge address array.

Source

pub fn flex_edgenum(&self) -> &[i32]

Immutable slice of the number of edges array.

Source

pub fn flex_edgenum_mut(&mut self) -> &mut [i32]

Mutable slice of the number of edges array.

Source

pub fn flex_elemadr(&self) -> &[i32]

Immutable slice of the first element address array.

Source

pub fn flex_elemadr_mut(&mut self) -> &mut [i32]

Mutable slice of the first element address array.

Source

pub fn flex_elemnum(&self) -> &[i32]

Immutable slice of the number of elements array.

Source

pub fn flex_elemnum_mut(&mut self) -> &mut [i32]

Mutable slice of the number of elements array.

Source

pub fn flex_elemdataadr(&self) -> &[i32]

Immutable slice of the first element vertex id address array.

Source

pub fn flex_elemdataadr_mut(&mut self) -> &mut [i32]

Mutable slice of the first element vertex id address array.

Source

pub fn flex_elemedgeadr(&self) -> &[i32]

Immutable slice of the first element edge id address array.

Source

pub fn flex_elemedgeadr_mut(&mut self) -> &mut [i32]

Mutable slice of the first element edge id address array.

Source

pub fn flex_shellnum(&self) -> &[i32]

Immutable slice of the number of shells array.

Source

pub fn flex_shellnum_mut(&mut self) -> &mut [i32]

Mutable slice of the number of shells array.

Source

pub fn flex_shelldataadr(&self) -> &[i32]

Immutable slice of the first shell data address array.

Source

pub fn flex_shelldataadr_mut(&mut self) -> &mut [i32]

Mutable slice of the first shell data address array.

Source

pub fn flex_evpairadr(&self) -> &[i32]

Immutable slice of the first evpair address array.

Source

pub fn flex_evpairadr_mut(&mut self) -> &mut [i32]

Mutable slice of the first evpair address array.

Source

pub fn flex_evpairnum(&self) -> &[i32]

Immutable slice of the number of evpairs array.

Source

pub fn flex_evpairnum_mut(&mut self) -> &mut [i32]

Mutable slice of the number of evpairs array.

Source

pub fn flex_texcoordadr(&self) -> &[i32]

Immutable slice of the address in flex_texcoord; -1: none array.

Source

pub fn flex_texcoordadr_mut(&mut self) -> &mut [i32]

Mutable slice of the address in flex_texcoord; -1: none array.

Source

pub fn flex_nodebodyid(&self) -> &[i32]

Immutable slice of the node body ids array.

Source

pub fn flex_nodebodyid_mut(&mut self) -> &mut [i32]

Mutable slice of the node body ids array.

Source

pub fn flex_vertbodyid(&self) -> &[i32]

Immutable slice of the vertex body ids array.

Source

pub fn flex_vertbodyid_mut(&mut self) -> &mut [i32]

Mutable slice of the vertex body ids array.

Source

pub fn flex_edge(&self) -> &[[i32; 2]]

Immutable slice of the edge vertex ids (2 per edge) array.

Source

pub fn flex_edge_mut(&mut self) -> &mut [[i32; 2]]

Mutable slice of the edge vertex ids (2 per edge) array.

Source

pub fn flex_edgeflap(&self) -> &[[i32; 2]]

Immutable slice of the adjacent vertex ids (dim=2 only) array.

Source

pub fn flex_edgeflap_mut(&mut self) -> &mut [[i32; 2]]

Mutable slice of the adjacent vertex ids (dim=2 only) array.

Source

pub fn flex_elem(&self) -> &[i32]

Immutable slice of the element vertex ids (dim+1 per elem) array.

Source

pub fn flex_elem_mut(&mut self) -> &mut [i32]

Mutable slice of the element vertex ids (dim+1 per elem) array.

Source

pub fn flex_elemtexcoord(&self) -> &[i32]

Immutable slice of the element texture coordinates (dim+1) array.

Source

pub fn flex_elemtexcoord_mut(&mut self) -> &mut [i32]

Mutable slice of the element texture coordinates (dim+1) array.

Source

pub fn flex_elemedge(&self) -> &[i32]

Immutable slice of the element edge ids array.

Source

pub fn flex_elemedge_mut(&mut self) -> &mut [i32]

Mutable slice of the element edge ids array.

Source

pub fn flex_elemlayer(&self) -> &[i32]

Immutable slice of the element distance from surface, 3D only array.

Source

pub fn flex_elemlayer_mut(&mut self) -> &mut [i32]

Mutable slice of the element distance from surface, 3D only array.

Source

pub fn flex_shell(&self) -> &[i32]

Immutable slice of the shell fragment vertex ids (dim per frag) array.

Source

pub fn flex_shell_mut(&mut self) -> &mut [i32]

Mutable slice of the shell fragment vertex ids (dim per frag) array.

Source

pub fn flex_evpair(&self) -> &[[i32; 2]]

Immutable slice of the (element, vertex) collision pairs array.

Source

pub fn flex_evpair_mut(&mut self) -> &mut [[i32; 2]]

Mutable slice of the (element, vertex) collision pairs array.

Source

pub fn flex_vert(&self) -> &[[MjtNum; 3]]

Immutable slice of the vertex positions in local body frames array.

Source

pub fn flex_vert_mut(&mut self) -> &mut [[MjtNum; 3]]

Mutable slice of the vertex positions in local body frames array.

Source

pub fn flex_vert0(&self) -> &[[MjtNum; 3]]

Immutable slice of the vertex positions in qpos0 on [0, 1]^d array.

Source

pub fn flex_vert0_mut(&mut self) -> &mut [[MjtNum; 3]]

Mutable slice of the vertex positions in qpos0 on [0, 1]^d array.

Source

pub fn flex_node(&self) -> &[[MjtNum; 3]]

Immutable slice of the node positions in local body frames array.

Source

pub fn flex_node_mut(&mut self) -> &mut [[MjtNum; 3]]

Mutable slice of the node positions in local body frames array.

Source

pub fn flex_node0(&self) -> &[[MjtNum; 3]]

Immutable slice of the Cartesian node positions in qpos0 array.

Source

pub fn flex_node0_mut(&mut self) -> &mut [[MjtNum; 3]]

Mutable slice of the Cartesian node positions in qpos0 array.

Source

pub fn flexedge_length0(&self) -> &[MjtNum]

Immutable slice of the edge lengths in qpos0 array.

Source

pub fn flexedge_length0_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the edge lengths in qpos0 array.

Source

pub fn flexedge_invweight0(&self) -> &[MjtNum]

Immutable slice of the edge inv. weight in qpos0 array.

Source

pub fn flexedge_invweight0_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the edge inv. weight in qpos0 array.

Source

pub fn flex_radius(&self) -> &[MjtNum]

Immutable slice of the radius around primitive element array.

Source

pub fn flex_radius_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the radius around primitive element array.

Source

pub fn flex_stiffness(&self) -> &[[MjtNum; 21]]

Immutable slice of the finite element stiffness matrix array.

Source

pub fn flex_stiffness_mut(&mut self) -> &mut [[MjtNum; 21]]

Mutable slice of the finite element stiffness matrix array.

Source

pub fn flex_bending(&self) -> &[[MjtNum; 17]]

Immutable slice of the bending stiffness array.

Source

pub fn flex_bending_mut(&mut self) -> &mut [[MjtNum; 17]]

Mutable slice of the bending stiffness array.

Source

pub fn flex_damping(&self) -> &[MjtNum]

Immutable slice of the Rayleigh’s damping coefficient array.

Source

pub fn flex_damping_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the Rayleigh’s damping coefficient array.

Source

pub fn flex_edgestiffness(&self) -> &[MjtNum]

Immutable slice of the edge stiffness array.

Source

pub fn flex_edgestiffness_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the edge stiffness array.

Source

pub fn flex_edgedamping(&self) -> &[MjtNum]

Immutable slice of the edge damping array.

Source

pub fn flex_edgedamping_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the edge damping array.

Source

pub fn flex_edgeequality(&self) -> &[bool]

Immutable slice of the is edge equality constraint defined array.

Source

pub fn flex_edgeequality_mut(&mut self) -> &mut [bool]

Mutable slice of the is edge equality constraint defined array.

Source

pub fn flex_rigid(&self) -> &[bool]

Immutable slice of the are all vertices in the same body array.

Source

pub fn flex_rigid_mut(&mut self) -> &mut [bool]

Mutable slice of the are all vertices in the same body array.

Source

pub fn flexedge_rigid(&self) -> &[bool]

Immutable slice of the are both edge vertices in same body array.

Source

pub fn flexedge_rigid_mut(&mut self) -> &mut [bool]

Mutable slice of the are both edge vertices in same body array.

Source

pub fn flex_centered(&self) -> &[bool]

Immutable slice of the are all vertex coordinates (0,0,0) array.

Source

pub fn flex_centered_mut(&mut self) -> &mut [bool]

Mutable slice of the are all vertex coordinates (0,0,0) array.

Source

pub fn flex_flatskin(&self) -> &[bool]

Immutable slice of the render flex skin with flat shading array.

Source

pub fn flex_flatskin_mut(&mut self) -> &mut [bool]

Mutable slice of the render flex skin with flat shading array.

Source

pub fn flex_bvhadr(&self) -> &[i32]

Immutable slice of the address of bvh root; -1: no bvh array.

Source

pub fn flex_bvhadr_mut(&mut self) -> &mut [i32]

Mutable slice of the address of bvh root; -1: no bvh array.

Source

pub fn flex_bvhnum(&self) -> &[i32]

Immutable slice of the number of bounding volumes array.

Source

pub fn flex_bvhnum_mut(&mut self) -> &mut [i32]

Mutable slice of the number of bounding volumes array.

Source

pub fn flex_rgba(&self) -> &[[f32; 4]]

Immutable slice of the rgba when material is omitted array.

Source

pub fn flex_rgba_mut(&mut self) -> &mut [[f32; 4]]

Mutable slice of the rgba when material is omitted array.

Source

pub fn flex_texcoord(&self) -> &[[f32; 2]]

Immutable slice of the vertex texture coordinates array.

Source

pub fn flex_texcoord_mut(&mut self) -> &mut [[f32; 2]]

Mutable slice of the vertex texture coordinates array.

Source

pub fn mesh_vertadr(&self) -> &[i32]

Immutable slice of the first vertex address array.

Source

pub fn mesh_vertadr_mut(&mut self) -> &mut [i32]

Mutable slice of the first vertex address array.

Source

pub fn mesh_vertnum(&self) -> &[i32]

Immutable slice of the number of vertices array.

Source

pub fn mesh_vertnum_mut(&mut self) -> &mut [i32]

Mutable slice of the number of vertices array.

Source

pub fn mesh_faceadr(&self) -> &[i32]

Immutable slice of the first face address array.

Source

pub fn mesh_faceadr_mut(&mut self) -> &mut [i32]

Mutable slice of the first face address array.

Source

pub fn mesh_facenum(&self) -> &[i32]

Immutable slice of the number of faces array.

Source

pub fn mesh_facenum_mut(&mut self) -> &mut [i32]

Mutable slice of the number of faces array.

Source

pub fn mesh_bvhadr(&self) -> &[i32]

Immutable slice of the address of bvh root array.

Source

pub fn mesh_bvhadr_mut(&mut self) -> &mut [i32]

Mutable slice of the address of bvh root array.

Source

pub fn mesh_bvhnum(&self) -> &[i32]

Immutable slice of the number of bvh array.

Source

pub fn mesh_bvhnum_mut(&mut self) -> &mut [i32]

Mutable slice of the number of bvh array.

Source

pub fn mesh_octadr(&self) -> &[i32]

Immutable slice of the address of octree root array.

Source

pub fn mesh_octadr_mut(&mut self) -> &mut [i32]

Mutable slice of the address of octree root array.

Source

pub fn mesh_octnum(&self) -> &[i32]

Immutable slice of the number of octree nodes array.

Source

pub fn mesh_octnum_mut(&mut self) -> &mut [i32]

Mutable slice of the number of octree nodes array.

Source

pub fn mesh_normaladr(&self) -> &[i32]

Immutable slice of the first normal address array.

Source

pub fn mesh_normaladr_mut(&mut self) -> &mut [i32]

Mutable slice of the first normal address array.

Source

pub fn mesh_normalnum(&self) -> &[i32]

Immutable slice of the number of normals array.

Source

pub fn mesh_normalnum_mut(&mut self) -> &mut [i32]

Mutable slice of the number of normals array.

Source

pub fn mesh_texcoordadr(&self) -> &[i32]

Immutable slice of the texcoord data address; -1: no texcoord array.

Source

pub fn mesh_texcoordadr_mut(&mut self) -> &mut [i32]

Mutable slice of the texcoord data address; -1: no texcoord array.

Source

pub fn mesh_texcoordnum(&self) -> &[i32]

Immutable slice of the number of texcoord array.

Source

pub fn mesh_texcoordnum_mut(&mut self) -> &mut [i32]

Mutable slice of the number of texcoord array.

Source

pub fn mesh_graphadr(&self) -> &[i32]

Immutable slice of the graph data address; -1: no graph array.

Source

pub fn mesh_graphadr_mut(&mut self) -> &mut [i32]

Mutable slice of the graph data address; -1: no graph array.

Source

pub fn mesh_vert(&self) -> &[[f32; 3]]

Immutable slice of the vertex positions for all meshes array.

Source

pub fn mesh_vert_mut(&mut self) -> &mut [[f32; 3]]

Mutable slice of the vertex positions for all meshes array.

Source

pub fn mesh_normal(&self) -> &[[f32; 3]]

Immutable slice of the normals for all meshes array.

Source

pub fn mesh_normal_mut(&mut self) -> &mut [[f32; 3]]

Mutable slice of the normals for all meshes array.

Source

pub fn mesh_texcoord(&self) -> &[[f32; 2]]

Immutable slice of the vertex texcoords for all meshes array.

Source

pub fn mesh_texcoord_mut(&mut self) -> &mut [[f32; 2]]

Mutable slice of the vertex texcoords for all meshes array.

Source

pub fn mesh_face(&self) -> &[[i32; 3]]

Immutable slice of the vertex face data array.

Source

pub fn mesh_face_mut(&mut self) -> &mut [[i32; 3]]

Mutable slice of the vertex face data array.

Source

pub fn mesh_facenormal(&self) -> &[[i32; 3]]

Immutable slice of the normal face data array.

Source

pub fn mesh_facenormal_mut(&mut self) -> &mut [[i32; 3]]

Mutable slice of the normal face data array.

Source

pub fn mesh_facetexcoord(&self) -> &[[i32; 3]]

Immutable slice of the texture face data array.

Source

pub fn mesh_facetexcoord_mut(&mut self) -> &mut [[i32; 3]]

Mutable slice of the texture face data array.

Source

pub fn mesh_graph(&self) -> &[i32]

Immutable slice of the convex graph data array.

Source

pub fn mesh_graph_mut(&mut self) -> &mut [i32]

Mutable slice of the convex graph data array.

Source

pub fn mesh_scale(&self) -> &[[MjtNum; 3]]

Immutable slice of the scaling applied to asset vertices array.

Source

pub fn mesh_scale_mut(&mut self) -> &mut [[MjtNum; 3]]

Mutable slice of the scaling applied to asset vertices array.

Source

pub fn mesh_pos(&self) -> &[[MjtNum; 3]]

Immutable slice of the translation applied to asset vertices array.

Source

pub fn mesh_pos_mut(&mut self) -> &mut [[MjtNum; 3]]

Mutable slice of the translation applied to asset vertices array.

Source

pub fn mesh_quat(&self) -> &[[MjtNum; 4]]

Immutable slice of the rotation applied to asset vertices array.

Source

pub fn mesh_quat_mut(&mut self) -> &mut [[MjtNum; 4]]

Mutable slice of the rotation applied to asset vertices array.

Source

pub fn mesh_pathadr(&self) -> &[i32]

Immutable slice of the address of asset path for mesh; -1: none array.

Source

pub fn mesh_pathadr_mut(&mut self) -> &mut [i32]

Mutable slice of the address of asset path for mesh; -1: none array.

Source

pub fn mesh_polynum(&self) -> &[i32]

Immutable slice of the number of polygons per mesh array.

Source

pub fn mesh_polynum_mut(&mut self) -> &mut [i32]

Mutable slice of the number of polygons per mesh array.

Source

pub fn mesh_polyadr(&self) -> &[i32]

Immutable slice of the first polygon address per mesh array.

Source

pub fn mesh_polyadr_mut(&mut self) -> &mut [i32]

Mutable slice of the first polygon address per mesh array.

Source

pub fn mesh_polynormal(&self) -> &[[MjtNum; 3]]

Immutable slice of the all polygon normals array.

Source

pub fn mesh_polynormal_mut(&mut self) -> &mut [[MjtNum; 3]]

Mutable slice of the all polygon normals array.

Source

pub fn mesh_polyvertadr(&self) -> &[i32]

Immutable slice of the polygon vertex start address array.

Source

pub fn mesh_polyvertadr_mut(&mut self) -> &mut [i32]

Mutable slice of the polygon vertex start address array.

Source

pub fn mesh_polyvertnum(&self) -> &[i32]

Immutable slice of the number of vertices per polygon array.

Source

pub fn mesh_polyvertnum_mut(&mut self) -> &mut [i32]

Mutable slice of the number of vertices per polygon array.

Source

pub fn mesh_polyvert(&self) -> &[i32]

Immutable slice of the all polygon vertices array.

Source

pub fn mesh_polyvert_mut(&mut self) -> &mut [i32]

Mutable slice of the all polygon vertices array.

Source

pub fn mesh_polymapadr(&self) -> &[i32]

Immutable slice of the first polygon address per vertex array.

Source

pub fn mesh_polymapadr_mut(&mut self) -> &mut [i32]

Mutable slice of the first polygon address per vertex array.

Source

pub fn mesh_polymapnum(&self) -> &[i32]

Immutable slice of the number of polygons per vertex array.

Source

pub fn mesh_polymapnum_mut(&mut self) -> &mut [i32]

Mutable slice of the number of polygons per vertex array.

Source

pub fn mesh_polymap(&self) -> &[i32]

Immutable slice of the vertex to polygon map array.

Source

pub fn mesh_polymap_mut(&mut self) -> &mut [i32]

Mutable slice of the vertex to polygon map array.

Source

pub fn skin_matid(&self) -> &[i32]

Immutable slice of the skin material id; -1: none array.

Source

pub fn skin_matid_mut(&mut self) -> &mut [i32]

Mutable slice of the skin material id; -1: none array.

Source

pub fn skin_group(&self) -> &[i32]

Immutable slice of the group for visibility array.

Source

pub fn skin_group_mut(&mut self) -> &mut [i32]

Mutable slice of the group for visibility array.

Source

pub fn skin_rgba(&self) -> &[[f32; 4]]

Immutable slice of the skin rgba array.

Source

pub fn skin_rgba_mut(&mut self) -> &mut [[f32; 4]]

Mutable slice of the skin rgba array.

Source

pub fn skin_inflate(&self) -> &[f32]

Immutable slice of the inflate skin in normal direction array.

Source

pub fn skin_inflate_mut(&mut self) -> &mut [f32]

Mutable slice of the inflate skin in normal direction array.

Source

pub fn skin_vertadr(&self) -> &[i32]

Immutable slice of the first vertex address array.

Source

pub fn skin_vertadr_mut(&mut self) -> &mut [i32]

Mutable slice of the first vertex address array.

Source

pub fn skin_vertnum(&self) -> &[i32]

Immutable slice of the number of vertices array.

Source

pub fn skin_vertnum_mut(&mut self) -> &mut [i32]

Mutable slice of the number of vertices array.

Source

pub fn skin_texcoordadr(&self) -> &[i32]

Immutable slice of the texcoord data address; -1: no texcoord array.

Source

pub fn skin_texcoordadr_mut(&mut self) -> &mut [i32]

Mutable slice of the texcoord data address; -1: no texcoord array.

Source

pub fn skin_faceadr(&self) -> &[i32]

Immutable slice of the first face address array.

Source

pub fn skin_faceadr_mut(&mut self) -> &mut [i32]

Mutable slice of the first face address array.

Source

pub fn skin_facenum(&self) -> &[i32]

Immutable slice of the number of faces array.

Source

pub fn skin_facenum_mut(&mut self) -> &mut [i32]

Mutable slice of the number of faces array.

Source

pub fn skin_boneadr(&self) -> &[i32]

Immutable slice of the first bone in skin array.

Source

pub fn skin_boneadr_mut(&mut self) -> &mut [i32]

Mutable slice of the first bone in skin array.

Source

pub fn skin_bonenum(&self) -> &[i32]

Immutable slice of the number of bones in skin array.

Source

pub fn skin_bonenum_mut(&mut self) -> &mut [i32]

Mutable slice of the number of bones in skin array.

Source

pub fn skin_vert(&self) -> &[[f32; 3]]

Immutable slice of the vertex positions for all skin meshes array.

Source

pub fn skin_vert_mut(&mut self) -> &mut [[f32; 3]]

Mutable slice of the vertex positions for all skin meshes array.

Source

pub fn skin_texcoord(&self) -> &[[f32; 2]]

Immutable slice of the vertex texcoords for all skin meshes array.

Source

pub fn skin_texcoord_mut(&mut self) -> &mut [[f32; 2]]

Mutable slice of the vertex texcoords for all skin meshes array.

Source

pub fn skin_face(&self) -> &[[i32; 3]]

Immutable slice of the triangle faces for all skin meshes array.

Source

pub fn skin_face_mut(&mut self) -> &mut [[i32; 3]]

Mutable slice of the triangle faces for all skin meshes array.

Source

pub fn skin_bonevertadr(&self) -> &[i32]

Immutable slice of the first vertex in each bone array.

Source

pub fn skin_bonevertadr_mut(&mut self) -> &mut [i32]

Mutable slice of the first vertex in each bone array.

Source

pub fn skin_bonevertnum(&self) -> &[i32]

Immutable slice of the number of vertices in each bone array.

Source

pub fn skin_bonevertnum_mut(&mut self) -> &mut [i32]

Mutable slice of the number of vertices in each bone array.

Source

pub fn skin_bonebindpos(&self) -> &[[f32; 3]]

Immutable slice of the bind pos of each bone array.

Source

pub fn skin_bonebindpos_mut(&mut self) -> &mut [[f32; 3]]

Mutable slice of the bind pos of each bone array.

Source

pub fn skin_bonebindquat(&self) -> &[[f32; 4]]

Immutable slice of the bind quat of each bone array.

Source

pub fn skin_bonebindquat_mut(&mut self) -> &mut [[f32; 4]]

Mutable slice of the bind quat of each bone array.

Source

pub fn skin_bonebodyid(&self) -> &[i32]

Immutable slice of the body id of each bone array.

Source

pub fn skin_bonebodyid_mut(&mut self) -> &mut [i32]

Mutable slice of the body id of each bone array.

Source

pub fn skin_bonevertid(&self) -> &[i32]

Immutable slice of the mesh ids of vertices in each bone array.

Source

pub fn skin_bonevertid_mut(&mut self) -> &mut [i32]

Mutable slice of the mesh ids of vertices in each bone array.

Source

pub fn skin_bonevertweight(&self) -> &[f32]

Immutable slice of the weights of vertices in each bone array.

Source

pub fn skin_bonevertweight_mut(&mut self) -> &mut [f32]

Mutable slice of the weights of vertices in each bone array.

Source

pub fn skin_pathadr(&self) -> &[i32]

Immutable slice of the address of asset path for skin; -1: none array.

Source

pub fn skin_pathadr_mut(&mut self) -> &mut [i32]

Mutable slice of the address of asset path for skin; -1: none array.

Source

pub fn hfield_size(&self) -> &[[MjtNum; 4]]

Immutable slice of the (x, y, z_top, z_bottom) array.

Source

pub fn hfield_size_mut(&mut self) -> &mut [[MjtNum; 4]]

Mutable slice of the (x, y, z_top, z_bottom) array.

Source

pub fn hfield_nrow(&self) -> &[i32]

Immutable slice of the number of rows in grid array.

Source

pub fn hfield_nrow_mut(&mut self) -> &mut [i32]

Mutable slice of the number of rows in grid array.

Source

pub fn hfield_ncol(&self) -> &[i32]

Immutable slice of the number of columns in grid array.

Source

pub fn hfield_ncol_mut(&mut self) -> &mut [i32]

Mutable slice of the number of columns in grid array.

Source

pub fn hfield_adr(&self) -> &[i32]

Immutable slice of the address in hfield_data array.

Source

pub fn hfield_adr_mut(&mut self) -> &mut [i32]

Mutable slice of the address in hfield_data array.

Source

pub fn hfield_data(&self) -> &[f32]

Immutable slice of the elevation data array.

Source

pub fn hfield_data_mut(&mut self) -> &mut [f32]

Mutable slice of the elevation data array.

Source

pub fn hfield_pathadr(&self) -> &[i32]

Immutable slice of the address of hfield asset path; -1: none array.

Source

pub fn hfield_pathadr_mut(&mut self) -> &mut [i32]

Mutable slice of the address of hfield asset path; -1: none array.

Source

pub fn tex_type(&self) -> &[MjtTexture]

Immutable slice of the texture type array.

Source

pub fn tex_type_mut(&mut self) -> &mut [MjtTexture]

Mutable slice of the texture type array.

Source

pub fn tex_colorspace(&self) -> &[MjtColorSpace]

Immutable slice of the texture colorspace array.

Source

pub fn tex_colorspace_mut(&mut self) -> &mut [MjtColorSpace]

Mutable slice of the texture colorspace array.

Source

pub fn tex_height(&self) -> &[i32]

Immutable slice of the number of rows in texture image array.

Source

pub fn tex_height_mut(&mut self) -> &mut [i32]

Mutable slice of the number of rows in texture image array.

Source

pub fn tex_width(&self) -> &[i32]

Immutable slice of the number of columns in texture image array.

Source

pub fn tex_width_mut(&mut self) -> &mut [i32]

Mutable slice of the number of columns in texture image array.

Source

pub fn tex_nchannel(&self) -> &[i32]

Immutable slice of the number of channels in texture image array.

Source

pub fn tex_nchannel_mut(&mut self) -> &mut [i32]

Mutable slice of the number of channels in texture image array.

Source

pub fn tex_adr(&self) -> &[i32]

Immutable slice of the start address in tex_data array.

Source

pub fn tex_adr_mut(&mut self) -> &mut [i32]

Mutable slice of the start address in tex_data array.

Source

pub fn tex_data(&self) -> &[MjtByte]

Immutable slice of the pixel values array.

Source

pub fn tex_data_mut(&mut self) -> &mut [MjtByte]

Mutable slice of the pixel values array.

Source

pub fn tex_pathadr(&self) -> &[i32]

Immutable slice of the address of texture asset path; -1: none array.

Source

pub fn tex_pathadr_mut(&mut self) -> &mut [i32]

Mutable slice of the address of texture asset path; -1: none array.

Source

pub fn mat_texid(&self) -> &[[i32; 10]]

Immutable slice of the indices of textures; -1: none array.

Source

pub fn mat_texid_mut(&mut self) -> &mut [[i32; 10]]

Mutable slice of the indices of textures; -1: none array.

Source

pub fn mat_texuniform(&self) -> &[bool]

Immutable slice of the make texture cube uniform array.

Source

pub fn mat_texuniform_mut(&mut self) -> &mut [bool]

Mutable slice of the make texture cube uniform array.

Source

pub fn mat_texrepeat(&self) -> &[[f32; 2]]

Immutable slice of the texture repetition for 2d mapping array.

Source

pub fn mat_texrepeat_mut(&mut self) -> &mut [[f32; 2]]

Mutable slice of the texture repetition for 2d mapping array.

Source

pub fn mat_emission(&self) -> &[f32]

Immutable slice of the emission (x rgb) array.

Source

pub fn mat_emission_mut(&mut self) -> &mut [f32]

Mutable slice of the emission (x rgb) array.

Source

pub fn mat_specular(&self) -> &[f32]

Immutable slice of the specular (x white) array.

Source

pub fn mat_specular_mut(&mut self) -> &mut [f32]

Mutable slice of the specular (x white) array.

Source

pub fn mat_shininess(&self) -> &[f32]

Immutable slice of the shininess coef array.

Source

pub fn mat_shininess_mut(&mut self) -> &mut [f32]

Mutable slice of the shininess coef array.

Source

pub fn mat_reflectance(&self) -> &[f32]

Immutable slice of the reflectance (0: disable) array.

Source

pub fn mat_reflectance_mut(&mut self) -> &mut [f32]

Mutable slice of the reflectance (0: disable) array.

Source

pub fn mat_metallic(&self) -> &[f32]

Immutable slice of the metallic coef array.

Source

pub fn mat_metallic_mut(&mut self) -> &mut [f32]

Mutable slice of the metallic coef array.

Source

pub fn mat_roughness(&self) -> &[f32]

Immutable slice of the roughness coef array.

Source

pub fn mat_roughness_mut(&mut self) -> &mut [f32]

Mutable slice of the roughness coef array.

Source

pub fn mat_rgba(&self) -> &[[f32; 4]]

Immutable slice of the rgba array.

Source

pub fn mat_rgba_mut(&mut self) -> &mut [[f32; 4]]

Mutable slice of the rgba array.

Source

pub fn pair_dim(&self) -> &[i32]

Immutable slice of the contact dimensionality array.

Source

pub fn pair_dim_mut(&mut self) -> &mut [i32]

Mutable slice of the contact dimensionality array.

Source

pub fn pair_geom1(&self) -> &[i32]

Immutable slice of the id of geom1 array.

Source

pub fn pair_geom1_mut(&mut self) -> &mut [i32]

Mutable slice of the id of geom1 array.

Source

pub fn pair_geom2(&self) -> &[i32]

Immutable slice of the id of geom2 array.

Source

pub fn pair_geom2_mut(&mut self) -> &mut [i32]

Mutable slice of the id of geom2 array.

Source

pub fn pair_signature(&self) -> &[i32]

Immutable slice of the body1 << 16 + body2 array.

Source

pub fn pair_signature_mut(&mut self) -> &mut [i32]

Mutable slice of the body1 << 16 + body2 array.

Source

pub fn pair_solref(&self) -> &[[MjtNum; 2]]

Immutable slice of the solver reference: contact normal array.

Source

pub fn pair_solref_mut(&mut self) -> &mut [[MjtNum; 2]]

Mutable slice of the solver reference: contact normal array.

Source

pub fn pair_solreffriction(&self) -> &[[MjtNum; 2]]

Immutable slice of the solver reference: contact friction array.

Source

pub fn pair_solreffriction_mut(&mut self) -> &mut [[MjtNum; 2]]

Mutable slice of the solver reference: contact friction array.

Source

pub fn pair_solimp(&self) -> &[[MjtNum; 5]]

Immutable slice of the solver impedance: contact array.

Source

pub fn pair_solimp_mut(&mut self) -> &mut [[MjtNum; 5]]

Mutable slice of the solver impedance: contact array.

Source

pub fn pair_margin(&self) -> &[MjtNum]

Immutable slice of the detect contact if dist<margin array.

Source

pub fn pair_margin_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the detect contact if dist<margin array.

Source

pub fn pair_gap(&self) -> &[MjtNum]

Immutable slice of the include in solver if dist<margin-gap array.

Source

pub fn pair_gap_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the include in solver if dist<margin-gap array.

Source

pub fn pair_friction(&self) -> &[[MjtNum; 5]]

Immutable slice of the tangent1, 2, spin, roll1, 2 array.

Source

pub fn pair_friction_mut(&mut self) -> &mut [[MjtNum; 5]]

Mutable slice of the tangent1, 2, spin, roll1, 2 array.

Source

pub fn exclude_signature(&self) -> &[i32]

Immutable slice of the body1 << 16 + body2 array.

Source

pub fn exclude_signature_mut(&mut self) -> &mut [i32]

Mutable slice of the body1 << 16 + body2 array.

Source

pub fn eq_type(&self) -> &[MjtEq]

Immutable slice of the constraint type array.

Source

pub fn eq_type_mut(&mut self) -> &mut [MjtEq]

Mutable slice of the constraint type array.

Source

pub fn eq_obj1id(&self) -> &[i32]

Immutable slice of the id of object 1 array.

Source

pub fn eq_obj1id_mut(&mut self) -> &mut [i32]

Mutable slice of the id of object 1 array.

Source

pub fn eq_obj2id(&self) -> &[i32]

Immutable slice of the id of object 2 array.

Source

pub fn eq_obj2id_mut(&mut self) -> &mut [i32]

Mutable slice of the id of object 2 array.

Source

pub fn eq_objtype(&self) -> &[MjtObj]

Immutable slice of the type of both objects array.

Source

pub fn eq_objtype_mut(&mut self) -> &mut [MjtObj]

Mutable slice of the type of both objects array.

Source

pub fn eq_active0(&self) -> &[bool]

Immutable slice of the initial enable/disable constraint state array.

Source

pub fn eq_active0_mut(&mut self) -> &mut [bool]

Mutable slice of the initial enable/disable constraint state array.

Source

pub fn eq_solref(&self) -> &[[MjtNum; 2]]

Immutable slice of the constraint solver reference array.

Source

pub fn eq_solref_mut(&mut self) -> &mut [[MjtNum; 2]]

Mutable slice of the constraint solver reference array.

Source

pub fn eq_solimp(&self) -> &[[MjtNum; 5]]

Immutable slice of the constraint solver impedance array.

Source

pub fn eq_solimp_mut(&mut self) -> &mut [[MjtNum; 5]]

Mutable slice of the constraint solver impedance array.

Source

pub fn eq_data(&self) -> &[[MjtNum; 11]]

Immutable slice of the numeric data for constraint array.

Source

pub fn eq_data_mut(&mut self) -> &mut [[MjtNum; 11]]

Mutable slice of the numeric data for constraint array.

Source

pub fn tendon_adr(&self) -> &[i32]

Immutable slice of the address of first object in tendon’s path array.

Source

pub fn tendon_adr_mut(&mut self) -> &mut [i32]

Mutable slice of the address of first object in tendon’s path array.

Source

pub fn tendon_num(&self) -> &[i32]

Immutable slice of the number of objects in tendon’s path array.

Source

pub fn tendon_num_mut(&mut self) -> &mut [i32]

Mutable slice of the number of objects in tendon’s path array.

Source

pub fn tendon_matid(&self) -> &[i32]

Immutable slice of the material id for rendering array.

Source

pub fn tendon_matid_mut(&mut self) -> &mut [i32]

Mutable slice of the material id for rendering array.

Source

pub fn tendon_group(&self) -> &[i32]

Immutable slice of the group for visibility array.

Source

pub fn tendon_group_mut(&mut self) -> &mut [i32]

Mutable slice of the group for visibility array.

Source

pub fn tendon_limited(&self) -> &[bool]

Immutable slice of the does tendon have length limits array.

Source

pub fn tendon_limited_mut(&mut self) -> &mut [bool]

Mutable slice of the does tendon have length limits array.

Source

pub fn tendon_actfrclimited(&self) -> &[bool]

Immutable slice of the does tendon have actuator force limits array.

Source

pub fn tendon_actfrclimited_mut(&mut self) -> &mut [bool]

Mutable slice of the does tendon have actuator force limits array.

Source

pub fn tendon_width(&self) -> &[MjtNum]

Immutable slice of the width for rendering array.

Source

pub fn tendon_width_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the width for rendering array.

Source

pub fn tendon_solref_lim(&self) -> &[[MjtNum; 2]]

Immutable slice of the constraint solver reference: limit array.

Source

pub fn tendon_solref_lim_mut(&mut self) -> &mut [[MjtNum; 2]]

Mutable slice of the constraint solver reference: limit array.

Source

pub fn tendon_solimp_lim(&self) -> &[[MjtNum; 5]]

Immutable slice of the constraint solver impedance: limit array.

Source

pub fn tendon_solimp_lim_mut(&mut self) -> &mut [[MjtNum; 5]]

Mutable slice of the constraint solver impedance: limit array.

Source

pub fn tendon_solref_fri(&self) -> &[[MjtNum; 2]]

Immutable slice of the constraint solver reference: friction array.

Source

pub fn tendon_solref_fri_mut(&mut self) -> &mut [[MjtNum; 2]]

Mutable slice of the constraint solver reference: friction array.

Source

pub fn tendon_solimp_fri(&self) -> &[[MjtNum; 5]]

Immutable slice of the constraint solver impedance: friction array.

Source

pub fn tendon_solimp_fri_mut(&mut self) -> &mut [[MjtNum; 5]]

Mutable slice of the constraint solver impedance: friction array.

Source

pub fn tendon_range(&self) -> &[[MjtNum; 2]]

Immutable slice of the tendon length limits array.

Source

pub fn tendon_range_mut(&mut self) -> &mut [[MjtNum; 2]]

Mutable slice of the tendon length limits array.

Source

pub fn tendon_actfrcrange(&self) -> &[[MjtNum; 2]]

Immutable slice of the range of total actuator force array.

Source

pub fn tendon_actfrcrange_mut(&mut self) -> &mut [[MjtNum; 2]]

Mutable slice of the range of total actuator force array.

Source

pub fn tendon_margin(&self) -> &[MjtNum]

Immutable slice of the min distance for limit detection array.

Source

pub fn tendon_margin_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the min distance for limit detection array.

Source

pub fn tendon_stiffness(&self) -> &[MjtNum]

Immutable slice of the stiffness coefficient array.

Source

pub fn tendon_stiffness_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the stiffness coefficient array.

Source

pub fn tendon_damping(&self) -> &[MjtNum]

Immutable slice of the damping coefficient array.

Source

pub fn tendon_damping_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the damping coefficient array.

Source

pub fn tendon_armature(&self) -> &[MjtNum]

Immutable slice of the inertia associated with tendon velocity array.

Source

pub fn tendon_armature_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the inertia associated with tendon velocity array.

Source

pub fn tendon_frictionloss(&self) -> &[MjtNum]

Immutable slice of the loss due to friction array.

Source

pub fn tendon_frictionloss_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the loss due to friction array.

Source

pub fn tendon_lengthspring(&self) -> &[[MjtNum; 2]]

Immutable slice of the spring resting length range array.

Source

pub fn tendon_lengthspring_mut(&mut self) -> &mut [[MjtNum; 2]]

Mutable slice of the spring resting length range array.

Source

pub fn tendon_length0(&self) -> &[MjtNum]

Immutable slice of the tendon length in qpos0 array.

Source

pub fn tendon_length0_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the tendon length in qpos0 array.

Source

pub fn tendon_invweight0(&self) -> &[MjtNum]

Immutable slice of the inv. weight in qpos0 array.

Source

pub fn tendon_invweight0_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the inv. weight in qpos0 array.

Source

pub fn tendon_rgba(&self) -> &[[f32; 4]]

Immutable slice of the rgba when material is omitted array.

Source

pub fn tendon_rgba_mut(&mut self) -> &mut [[f32; 4]]

Mutable slice of the rgba when material is omitted array.

Source

pub fn wrap_type(&self) -> &[MjtWrap]

Immutable slice of the wrap object type array.

Source

pub fn wrap_type_mut(&mut self) -> &mut [MjtWrap]

Mutable slice of the wrap object type array.

Source

pub fn wrap_objid(&self) -> &[i32]

Immutable slice of the object id: geom, site, joint array.

Source

pub fn wrap_objid_mut(&mut self) -> &mut [i32]

Mutable slice of the object id: geom, site, joint array.

Source

pub fn wrap_prm(&self) -> &[MjtNum]

Immutable slice of the divisor, joint coef, or site id array.

Source

pub fn wrap_prm_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the divisor, joint coef, or site id array.

Source

pub fn actuator_trntype(&self) -> &[MjtTrn]

Immutable slice of the transmission type array.

Source

pub fn actuator_trntype_mut(&mut self) -> &mut [MjtTrn]

Mutable slice of the transmission type array.

Source

pub fn actuator_dyntype(&self) -> &[MjtDyn]

Immutable slice of the dynamics type array.

Source

pub fn actuator_dyntype_mut(&mut self) -> &mut [MjtDyn]

Mutable slice of the dynamics type array.

Source

pub fn actuator_gaintype(&self) -> &[MjtGain]

Immutable slice of the gain type array.

Source

pub fn actuator_gaintype_mut(&mut self) -> &mut [MjtGain]

Mutable slice of the gain type array.

Source

pub fn actuator_biastype(&self) -> &[MjtBias]

Immutable slice of the bias type array.

Source

pub fn actuator_biastype_mut(&mut self) -> &mut [MjtBias]

Mutable slice of the bias type array.

Source

pub fn actuator_trnid(&self) -> &[[i32; 2]]

Immutable slice of the transmission id: joint, tendon, site array.

Source

pub fn actuator_trnid_mut(&mut self) -> &mut [[i32; 2]]

Mutable slice of the transmission id: joint, tendon, site array.

Source

pub fn actuator_actadr(&self) -> &[i32]

Immutable slice of the first activation address; -1: stateless array.

Source

pub fn actuator_actadr_mut(&mut self) -> &mut [i32]

Mutable slice of the first activation address; -1: stateless array.

Source

pub fn actuator_actnum(&self) -> &[i32]

Immutable slice of the number of activation variables array.

Source

pub fn actuator_actnum_mut(&mut self) -> &mut [i32]

Mutable slice of the number of activation variables array.

Source

pub fn actuator_group(&self) -> &[i32]

Immutable slice of the group for visibility array.

Source

pub fn actuator_group_mut(&mut self) -> &mut [i32]

Mutable slice of the group for visibility array.

Source

pub fn actuator_ctrllimited(&self) -> &[bool]

Immutable slice of the is control limited array.

Source

pub fn actuator_ctrllimited_mut(&mut self) -> &mut [bool]

Mutable slice of the is control limited array.

Source

pub fn actuator_actlimited(&self) -> &[bool]

Immutable slice of the is activation limited array.

Source

pub fn actuator_actlimited_mut(&mut self) -> &mut [bool]

Mutable slice of the is activation limited array.

Source

pub fn actuator_dynprm(&self) -> &[[MjtNum; 10]]

Immutable slice of the dynamics parameters array.

Source

pub fn actuator_dynprm_mut(&mut self) -> &mut [[MjtNum; 10]]

Mutable slice of the dynamics parameters array.

Source

pub fn actuator_gainprm(&self) -> &[[MjtNum; 10]]

Immutable slice of the gain parameters array.

Source

pub fn actuator_gainprm_mut(&mut self) -> &mut [[MjtNum; 10]]

Mutable slice of the gain parameters array.

Source

pub fn actuator_biasprm(&self) -> &[[MjtNum; 10]]

Immutable slice of the bias parameters array.

Source

pub fn actuator_biasprm_mut(&mut self) -> &mut [[MjtNum; 10]]

Mutable slice of the bias parameters array.

Source

pub fn actuator_actearly(&self) -> &[bool]

Immutable slice of the step activation before force array.

Source

pub fn actuator_actearly_mut(&mut self) -> &mut [bool]

Mutable slice of the step activation before force array.

Source

pub fn actuator_ctrlrange(&self) -> &[[MjtNum; 2]]

Immutable slice of the range of controls array.

Source

pub fn actuator_ctrlrange_mut(&mut self) -> &mut [[MjtNum; 2]]

Mutable slice of the range of controls array.

Source

pub fn actuator_forcerange(&self) -> &[[MjtNum; 2]]

Immutable slice of the range of forces array.

Source

pub fn actuator_forcerange_mut(&mut self) -> &mut [[MjtNum; 2]]

Mutable slice of the range of forces array.

Source

pub fn actuator_actrange(&self) -> &[[MjtNum; 2]]

Immutable slice of the range of activations array.

Source

pub fn actuator_actrange_mut(&mut self) -> &mut [[MjtNum; 2]]

Mutable slice of the range of activations array.

Source

pub fn actuator_gear(&self) -> &[[MjtNum; 6]]

Immutable slice of the scale length and transmitted force array.

Source

pub fn actuator_gear_mut(&mut self) -> &mut [[MjtNum; 6]]

Mutable slice of the scale length and transmitted force array.

Source

pub fn actuator_cranklength(&self) -> &[MjtNum]

Immutable slice of the crank length for slider-crank array.

Source

pub fn actuator_cranklength_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the crank length for slider-crank array.

Source

pub fn actuator_acc0(&self) -> &[MjtNum]

Immutable slice of the acceleration from unit force in qpos0 array.

Source

pub fn actuator_acc0_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the acceleration from unit force in qpos0 array.

Source

pub fn actuator_length0(&self) -> &[MjtNum]

Immutable slice of the actuator length in qpos0 array.

Source

pub fn actuator_length0_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the actuator length in qpos0 array.

Source

pub fn actuator_lengthrange(&self) -> &[[MjtNum; 2]]

Immutable slice of the feasible actuator length range array.

Source

pub fn actuator_lengthrange_mut(&mut self) -> &mut [[MjtNum; 2]]

Mutable slice of the feasible actuator length range array.

Source

pub fn actuator_plugin(&self) -> &[i32]

Immutable slice of the plugin instance id; -1: not a plugin array.

Source

pub fn actuator_plugin_mut(&mut self) -> &mut [i32]

Mutable slice of the plugin instance id; -1: not a plugin array.

Source

pub fn sensor_type(&self) -> &[MjtSensor]

Immutable slice of the sensor type array.

Source

pub fn sensor_type_mut(&mut self) -> &mut [MjtSensor]

Mutable slice of the sensor type array.

Source

pub fn sensor_datatype(&self) -> &[MjtDataType]

Immutable slice of the numeric data type array.

Source

pub fn sensor_datatype_mut(&mut self) -> &mut [MjtDataType]

Mutable slice of the numeric data type array.

Source

pub fn sensor_needstage(&self) -> &[MjtStage]

Immutable slice of the required compute stage array.

Source

pub fn sensor_needstage_mut(&mut self) -> &mut [MjtStage]

Mutable slice of the required compute stage array.

Source

pub fn sensor_objtype(&self) -> &[MjtObj]

Immutable slice of the type of sensorized object array.

Source

pub fn sensor_objtype_mut(&mut self) -> &mut [MjtObj]

Mutable slice of the type of sensorized object array.

Source

pub fn sensor_objid(&self) -> &[i32]

Immutable slice of the id of sensorized object array.

Source

pub fn sensor_objid_mut(&mut self) -> &mut [i32]

Mutable slice of the id of sensorized object array.

Source

pub fn sensor_reftype(&self) -> &[MjtObj]

Immutable slice of the type of reference frame array.

Source

pub fn sensor_reftype_mut(&mut self) -> &mut [MjtObj]

Mutable slice of the type of reference frame array.

Source

pub fn sensor_refid(&self) -> &[i32]

Immutable slice of the id of reference frame; -1: global frame array.

Source

pub fn sensor_refid_mut(&mut self) -> &mut [i32]

Mutable slice of the id of reference frame; -1: global frame array.

Source

pub fn sensor_intprm(&self) -> &[[i32; 3]]

Immutable slice of the sensor parameters array.

Source

pub fn sensor_intprm_mut(&mut self) -> &mut [[i32; 3]]

Mutable slice of the sensor parameters array.

Source

pub fn sensor_dim(&self) -> &[i32]

Immutable slice of the number of scalar outputs array.

Source

pub fn sensor_dim_mut(&mut self) -> &mut [i32]

Mutable slice of the number of scalar outputs array.

Source

pub fn sensor_adr(&self) -> &[i32]

Immutable slice of the address in sensor array array.

Source

pub fn sensor_adr_mut(&mut self) -> &mut [i32]

Mutable slice of the address in sensor array array.

Source

pub fn sensor_cutoff(&self) -> &[MjtNum]

Immutable slice of the cutoff for real and positive; 0: ignore array.

Source

pub fn sensor_cutoff_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the cutoff for real and positive; 0: ignore array.

Source

pub fn sensor_noise(&self) -> &[MjtNum]

Immutable slice of the noise standard deviation array.

Source

pub fn sensor_noise_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the noise standard deviation array.

Source

pub fn sensor_plugin(&self) -> &[i32]

Immutable slice of the plugin instance id; -1: not a plugin array.

Source

pub fn sensor_plugin_mut(&mut self) -> &mut [i32]

Mutable slice of the plugin instance id; -1: not a plugin array.

Source

pub fn plugin(&self) -> &[i32]

Immutable slice of the globally registered plugin slot number array.

Source

pub fn plugin_mut(&mut self) -> &mut [i32]

Mutable slice of the globally registered plugin slot number array.

Source

pub fn plugin_stateadr(&self) -> &[i32]

Immutable slice of the address in the plugin state array array.

Source

pub fn plugin_stateadr_mut(&mut self) -> &mut [i32]

Mutable slice of the address in the plugin state array array.

Source

pub fn plugin_statenum(&self) -> &[i32]

Immutable slice of the number of states in the plugin instance array.

Source

pub fn plugin_statenum_mut(&mut self) -> &mut [i32]

Mutable slice of the number of states in the plugin instance array.

Source

pub fn plugin_attr(&self) -> &[i8]

Immutable slice of the config attributes of plugin instances array.

Source

pub fn plugin_attr_mut(&mut self) -> &mut [i8]

Mutable slice of the config attributes of plugin instances array.

Source

pub fn plugin_attradr(&self) -> &[i32]

Immutable slice of the address to each instance’s config attrib array.

Source

pub fn plugin_attradr_mut(&mut self) -> &mut [i32]

Mutable slice of the address to each instance’s config attrib array.

Source

pub fn numeric_adr(&self) -> &[i32]

Immutable slice of the address of field in numeric_data array.

Source

pub fn numeric_adr_mut(&mut self) -> &mut [i32]

Mutable slice of the address of field in numeric_data array.

Source

pub fn numeric_size(&self) -> &[i32]

Immutable slice of the size of numeric field array.

Source

pub fn numeric_size_mut(&mut self) -> &mut [i32]

Mutable slice of the size of numeric field array.

Source

pub fn numeric_data(&self) -> &[MjtNum]

Immutable slice of the array of all numeric fields array.

Source

pub fn numeric_data_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the array of all numeric fields array.

Source

pub fn text_adr(&self) -> &[i32]

Immutable slice of the address of text in text_data array.

Source

pub fn text_adr_mut(&mut self) -> &mut [i32]

Mutable slice of the address of text in text_data array.

Source

pub fn text_size(&self) -> &[i32]

Immutable slice of the size of text field (strlen+1) array.

Source

pub fn text_size_mut(&mut self) -> &mut [i32]

Mutable slice of the size of text field (strlen+1) array.

Source

pub fn text_data(&self) -> &[i8]

Immutable slice of the array of all text fields (0-terminated) array.

Source

pub fn text_data_mut(&mut self) -> &mut [i8]

Mutable slice of the array of all text fields (0-terminated) array.

Source

pub fn tuple_adr(&self) -> &[i32]

Immutable slice of the address of text in text_data array.

Source

pub fn tuple_adr_mut(&mut self) -> &mut [i32]

Mutable slice of the address of text in text_data array.

Source

pub fn tuple_size(&self) -> &[i32]

Immutable slice of the number of objects in tuple array.

Source

pub fn tuple_size_mut(&mut self) -> &mut [i32]

Mutable slice of the number of objects in tuple array.

Source

pub fn tuple_objtype(&self) -> &[i32]

Immutable slice of the array of object types in all tuples array.

Source

pub fn tuple_objtype_mut(&mut self) -> &mut [i32]

Mutable slice of the array of object types in all tuples array.

Source

pub fn tuple_objid(&self) -> &[i32]

Immutable slice of the array of object ids in all tuples array.

Source

pub fn tuple_objid_mut(&mut self) -> &mut [i32]

Mutable slice of the array of object ids in all tuples array.

Source

pub fn tuple_objprm(&self) -> &[MjtNum]

Immutable slice of the array of object params in all tuples array.

Source

pub fn tuple_objprm_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the array of object params in all tuples array.

Source

pub fn key_time(&self) -> &[MjtNum]

Immutable slice of the key time array.

Source

pub fn key_time_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the key time array.

Source

pub fn name_bodyadr(&self) -> &[i32]

Immutable slice of the body name pointers array.

Source

pub fn name_bodyadr_mut(&mut self) -> &mut [i32]

Mutable slice of the body name pointers array.

Source

pub fn name_jntadr(&self) -> &[i32]

Immutable slice of the joint name pointers array.

Source

pub fn name_jntadr_mut(&mut self) -> &mut [i32]

Mutable slice of the joint name pointers array.

Source

pub fn name_geomadr(&self) -> &[i32]

Immutable slice of the geom name pointers array.

Source

pub fn name_geomadr_mut(&mut self) -> &mut [i32]

Mutable slice of the geom name pointers array.

Source

pub fn name_siteadr(&self) -> &[i32]

Immutable slice of the site name pointers array.

Source

pub fn name_siteadr_mut(&mut self) -> &mut [i32]

Mutable slice of the site name pointers array.

Source

pub fn name_camadr(&self) -> &[i32]

Immutable slice of the camera name pointers array.

Source

pub fn name_camadr_mut(&mut self) -> &mut [i32]

Mutable slice of the camera name pointers array.

Source

pub fn name_lightadr(&self) -> &[i32]

Immutable slice of the light name pointers array.

Source

pub fn name_lightadr_mut(&mut self) -> &mut [i32]

Mutable slice of the light name pointers array.

Source

pub fn name_flexadr(&self) -> &[i32]

Immutable slice of the flex name pointers array.

Source

pub fn name_flexadr_mut(&mut self) -> &mut [i32]

Mutable slice of the flex name pointers array.

Source

pub fn name_meshadr(&self) -> &[i32]

Immutable slice of the mesh name pointers array.

Source

pub fn name_meshadr_mut(&mut self) -> &mut [i32]

Mutable slice of the mesh name pointers array.

Source

pub fn name_skinadr(&self) -> &[i32]

Immutable slice of the skin name pointers array.

Source

pub fn name_skinadr_mut(&mut self) -> &mut [i32]

Mutable slice of the skin name pointers array.

Source

pub fn name_hfieldadr(&self) -> &[i32]

Immutable slice of the hfield name pointers array.

Source

pub fn name_hfieldadr_mut(&mut self) -> &mut [i32]

Mutable slice of the hfield name pointers array.

Source

pub fn name_texadr(&self) -> &[i32]

Immutable slice of the texture name pointers array.

Source

pub fn name_texadr_mut(&mut self) -> &mut [i32]

Mutable slice of the texture name pointers array.

Source

pub fn name_matadr(&self) -> &[i32]

Immutable slice of the material name pointers array.

Source

pub fn name_matadr_mut(&mut self) -> &mut [i32]

Mutable slice of the material name pointers array.

Source

pub fn name_pairadr(&self) -> &[i32]

Immutable slice of the geom pair name pointers array.

Source

pub fn name_pairadr_mut(&mut self) -> &mut [i32]

Mutable slice of the geom pair name pointers array.

Source

pub fn name_excludeadr(&self) -> &[i32]

Immutable slice of the exclude name pointers array.

Source

pub fn name_excludeadr_mut(&mut self) -> &mut [i32]

Mutable slice of the exclude name pointers array.

Source

pub fn name_eqadr(&self) -> &[i32]

Immutable slice of the equality constraint name pointers array.

Source

pub fn name_eqadr_mut(&mut self) -> &mut [i32]

Mutable slice of the equality constraint name pointers array.

Source

pub fn name_tendonadr(&self) -> &[i32]

Immutable slice of the tendon name pointers array.

Source

pub fn name_tendonadr_mut(&mut self) -> &mut [i32]

Mutable slice of the tendon name pointers array.

Source

pub fn name_actuatoradr(&self) -> &[i32]

Immutable slice of the actuator name pointers array.

Source

pub fn name_actuatoradr_mut(&mut self) -> &mut [i32]

Mutable slice of the actuator name pointers array.

Source

pub fn name_sensoradr(&self) -> &[i32]

Immutable slice of the sensor name pointers array.

Source

pub fn name_sensoradr_mut(&mut self) -> &mut [i32]

Mutable slice of the sensor name pointers array.

Source

pub fn name_numericadr(&self) -> &[i32]

Immutable slice of the numeric name pointers array.

Source

pub fn name_numericadr_mut(&mut self) -> &mut [i32]

Mutable slice of the numeric name pointers array.

Source

pub fn name_textadr(&self) -> &[i32]

Immutable slice of the text name pointers array.

Source

pub fn name_textadr_mut(&mut self) -> &mut [i32]

Mutable slice of the text name pointers array.

Source

pub fn name_tupleadr(&self) -> &[i32]

Immutable slice of the tuple name pointers array.

Source

pub fn name_tupleadr_mut(&mut self) -> &mut [i32]

Mutable slice of the tuple name pointers array.

Source

pub fn name_keyadr(&self) -> &[i32]

Immutable slice of the keyframe name pointers array.

Source

pub fn name_keyadr_mut(&mut self) -> &mut [i32]

Mutable slice of the keyframe name pointers array.

Source

pub fn name_pluginadr(&self) -> &[i32]

Immutable slice of the plugin instance name pointers array.

Source

pub fn name_pluginadr_mut(&mut self) -> &mut [i32]

Mutable slice of the plugin instance name pointers array.

Source

pub fn names(&self) -> &[i8]

Immutable slice of the names of all objects, 0-terminated array.

Source

pub fn names_mut(&mut self) -> &mut [i8]

Mutable slice of the names of all objects, 0-terminated array.

Source

pub fn names_map(&self) -> &[i32]

Immutable slice of the internal hash map of names array.

Source

pub fn names_map_mut(&mut self) -> &mut [i32]

Mutable slice of the internal hash map of names array.

Source

pub fn paths(&self) -> &[i8]

Immutable slice of the paths to assets, 0-terminated array.

Source

pub fn paths_mut(&mut self) -> &mut [i8]

Mutable slice of the paths to assets, 0-terminated array.

Source

pub fn b_rownnz(&self) -> &[i32]

Immutable slice of the body-dof: non-zeros in each row array.

Source

pub fn b_rownnz_mut(&mut self) -> &mut [i32]

Mutable slice of the body-dof: non-zeros in each row array.

Source

pub fn b_rowadr(&self) -> &[i32]

Immutable slice of the body-dof: row addresses array.

Source

pub fn b_rowadr_mut(&mut self) -> &mut [i32]

Mutable slice of the body-dof: row addresses array.

Source

pub fn b_colind(&self) -> &[i32]

Immutable slice of the body-dof: column indices array.

Source

pub fn b_colind_mut(&mut self) -> &mut [i32]

Mutable slice of the body-dof: column indices array.

Source

pub fn m_rownnz(&self) -> &[i32]

Immutable slice of the reduced inertia: non-zeros in each row array.

Source

pub fn m_rownnz_mut(&mut self) -> &mut [i32]

Mutable slice of the reduced inertia: non-zeros in each row array.

Source

pub fn m_rowadr(&self) -> &[i32]

Immutable slice of the reduced inertia: row addresses array.

Source

pub fn m_rowadr_mut(&mut self) -> &mut [i32]

Mutable slice of the reduced inertia: row addresses array.

Source

pub fn m_colind(&self) -> &[i32]

Immutable slice of the reduced inertia: column indices array.

Source

pub fn m_colind_mut(&mut self) -> &mut [i32]

Mutable slice of the reduced inertia: column indices array.

Source

pub fn map_m2_m(&self) -> &[i32]

Immutable slice of the index mapping from qM to M array.

Source

pub fn map_m2_m_mut(&mut self) -> &mut [i32]

Mutable slice of the index mapping from qM to M array.

Source

pub fn d_rownnz(&self) -> &[i32]

Immutable slice of the full inertia: non-zeros in each row array.

Source

pub fn d_rownnz_mut(&mut self) -> &mut [i32]

Mutable slice of the full inertia: non-zeros in each row array.

Source

pub fn d_rowadr(&self) -> &[i32]

Immutable slice of the full inertia: row addresses array.

Source

pub fn d_rowadr_mut(&mut self) -> &mut [i32]

Mutable slice of the full inertia: row addresses array.

Source

pub fn d_diag(&self) -> &[i32]

Immutable slice of the full inertia: index of diagonal element array.

Source

pub fn d_diag_mut(&mut self) -> &mut [i32]

Mutable slice of the full inertia: index of diagonal element array.

Source

pub fn d_colind(&self) -> &[i32]

Immutable slice of the full inertia: column indices array.

Source

pub fn d_colind_mut(&mut self) -> &mut [i32]

Mutable slice of the full inertia: column indices array.

Source

pub fn map_m2_d(&self) -> &[i32]

Immutable slice of the index mapping from M to D array.

Source

pub fn map_m2_d_mut(&mut self) -> &mut [i32]

Mutable slice of the index mapping from M to D array.

Source

pub fn map_d2_m(&self) -> &[i32]

Immutable slice of the index mapping from D to M array.

Source

pub fn map_d2_m_mut(&mut self) -> &mut [i32]

Mutable slice of the index mapping from D to M array.

Source

pub fn key_qpos(&self) -> &[MjtNum]

Immutable slice of the key position array.

Source

pub fn key_qpos_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the key position array.

Source

pub fn key_qvel(&self) -> &[MjtNum]

Immutable slice of the key velocity array.

Source

pub fn key_qvel_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the key velocity array.

Source

pub fn key_act(&self) -> &[MjtNum]

Immutable slice of the key activation array.

Source

pub fn key_act_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the key activation array.

Source

pub fn key_ctrl(&self) -> &[MjtNum]

Immutable slice of the key control array.

Source

pub fn key_ctrl_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the key control array.

Source

pub fn sensor_user(&self) -> &[MjtNum]

Immutable slice of the user data array.

Source

pub fn sensor_user_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the user data array.

Source

pub fn actuator_user(&self) -> &[MjtNum]

Immutable slice of the user data array.

Source

pub fn actuator_user_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the user data array.

Source

pub fn tendon_user(&self) -> &[MjtNum]

Immutable slice of the user data array.

Source

pub fn tendon_user_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the user data array.

Source

pub fn cam_user(&self) -> &[MjtNum]

Immutable slice of the user data array.

Source

pub fn cam_user_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the user data array.

Source

pub fn site_user(&self) -> &[MjtNum]

Immutable slice of the user data array.

Source

pub fn site_user_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the user data array.

Source

pub fn geom_user(&self) -> &[MjtNum]

Immutable slice of the user data array.

Source

pub fn geom_user_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the user data array.

Source

pub fn jnt_user(&self) -> &[MjtNum]

Immutable slice of the user data array.

Source

pub fn jnt_user_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the user data array.

Source

pub fn body_user(&self) -> &[MjtNum]

Immutable slice of the user data array.

Source

pub fn body_user_mut(&mut self) -> &mut [MjtNum]

Mutable slice of the user data array.

Trait Implementations§

Source§

impl Debug for MjModel

Source§

fn fmt(&self, f: &mut Formatter<'_>) -> Result

Formats the value using the given formatter. Read more
Source§

impl Drop for MjModel

Source§

fn drop(&mut self)

Executes the destructor for this type. Read more
Source§

impl Send for MjModel

Source§

impl Sync for MjModel

Auto Trait Implementations§

Blanket Implementations§

Source§

impl<T> Any for T
where T: 'static + ?Sized,

Source§

fn type_id(&self) -> TypeId

Gets the TypeId of self. Read more
Source§

impl<T> Borrow<T> for T
where T: ?Sized,

Source§

fn borrow(&self) -> &T

Immutably borrows from an owned value. Read more
Source§

impl<T> BorrowMut<T> for T
where T: ?Sized,

Source§

fn borrow_mut(&mut self) -> &mut T

Mutably borrows from an owned value. Read more
Source§

impl<T> Downcast for T
where T: Any,

Source§

fn into_any(self: Box<T>) -> Box<dyn Any>

Convert Box<dyn Trait> (where Trait: Downcast) to Box<dyn Any>. Box<dyn Any> can then be further downcast into Box<ConcreteType> where ConcreteType implements Trait.
Source§

fn into_any_rc(self: Rc<T>) -> Rc<dyn Any>

Convert Rc<Trait> (where Trait: Downcast) to Rc<Any>. Rc<Any> can then be further downcast into Rc<ConcreteType> where ConcreteType implements Trait.
Source§

fn as_any(&self) -> &(dyn Any + 'static)

Convert &Trait (where Trait: Downcast) to &Any. This is needed since Rust cannot generate &Any’s vtable from &Trait’s.
Source§

fn as_any_mut(&mut self) -> &mut (dyn Any + 'static)

Convert &mut Trait (where Trait: Downcast) to &Any. This is needed since Rust cannot generate &mut Any’s vtable from &mut Trait’s.
Source§

impl<T> DowncastSync for T
where T: Any + Send + Sync,

Source§

fn into_any_arc(self: Arc<T>) -> Arc<dyn Any + Send + Sync>

Convert Arc<Trait> (where Trait: Downcast) to Arc<Any>. Arc<Any> can then be further downcast into Arc<ConcreteType> where ConcreteType implements Trait.
Source§

impl<T> From<T> for T

Source§

fn from(t: T) -> T

Returns the argument unchanged.

Source§

impl<T> Instrument for T

Source§

fn instrument(self, span: Span) -> Instrumented<Self>

Instruments this type with the provided Span, returning an Instrumented wrapper. Read more
Source§

fn in_current_span(self) -> Instrumented<Self>

Instruments this type with the current Span, returning an Instrumented wrapper. Read more
Source§

impl<T, U> Into<U> for T
where U: From<T>,

Source§

fn into(self) -> U

Calls U::from(self).

That is, this conversion is whatever the implementation of From<T> for U chooses to do.

Source§

impl<T, U> TryFrom<U> for T
where U: Into<T>,

Source§

type Error = Infallible

The type returned in the event of a conversion error.
Source§

fn try_from(value: U) -> Result<T, <T as TryFrom<U>>::Error>

Performs the conversion.
Source§

impl<T, U> TryInto<U> for T
where U: TryFrom<T>,

Source§

type Error = <U as TryFrom<T>>::Error

The type returned in the event of a conversion error.
Source§

fn try_into(self) -> Result<U, <U as TryFrom<T>>::Error>

Performs the conversion.
Source§

impl<T> WithSubscriber for T

Source§

fn with_subscriber<S>(self, subscriber: S) -> WithDispatch<Self>
where S: Into<Dispatch>,

Attaches the provided Subscriber to this type, returning a WithDispatch wrapper. Read more
Source§

fn with_current_subscriber(self) -> WithDispatch<Self>

Attaches the current default Subscriber to this type, returning a WithDispatch wrapper. Read more