From e4fbde331836f438d252e29e914cb4a5998caa94 Mon Sep 17 00:00:00 2001 From: kanarus Date: Mon, 15 Sep 2025 03:11:30 +0900 Subject: [PATCH] rename: unify struct naming convention and revert version to 0.1(.1) --- Cargo.toml | 2 +- README.md | 10 +-- examples/visualize_left_object.rs | 6 +- src/functions/assets.rs | 12 +-- src/functions/attachment.rs | 6 +- src/functions/components.rs | 24 ++--- src/functions/element_initialization.rs | 6 +- src/functions/error_and_memory.rs | 6 +- src/functions/find_and_get_utilities.rs | 24 ++--- src/functions/initialization.rs | 64 +++++++------- src/functions/interaction.rs | 42 ++++----- src/functions/main_simulation.rs | 20 ++--- src/functions/non_tree_elements.rs | 28 +++--- src/functions/opengl_rendering.rs | 54 ++++++------ src/functions/parse_and_compile.rs | 30 +++---- src/functions/ray_casting.rs | 20 ++--- src/functions/sub_components.rs | 66 +++++++------- src/functions/support.rs | 112 ++++++++++++------------ src/functions/ui_framework.rs | 10 +-- src/functions/visualization.rs | 48 +++++----- src/id.rs | 12 +-- src/types.rs | 1 + src/types/mjdata.rs | 46 +++++----- src/types/mjmodel.rs | 14 +-- src/types/model_editing.rs | 10 +-- src/types/rendering.rs | 16 ++-- src/types/visualization.rs | 20 ++--- 27 files changed, 352 insertions(+), 357 deletions(-) diff --git a/Cargo.toml b/Cargo.toml index c349ca8..ef13bb2 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -1,6 +1,6 @@ [package] name = "rusty_mujoco" -version = "0.2.0" +version = "0.1.1" edition = "2024" authors = ["kanarus "] documentation = "https://docs.rs/rusty_mujoco" diff --git a/README.md b/README.md index 5a48f12..7b4704e 100644 --- a/README.md +++ b/README.md @@ -57,7 +57,7 @@ *Cargo.toml* ```toml [dependencies] -rusty_mujoco = "0.2" +rusty_mujoco = "0.1" ``` *src/main.rs* @@ -69,17 +69,11 @@ fn main() { See the [examples](./examples) directory for working examples. -### Note - -- Binding policy: +### Binding Philosophy: - implement based on [rust-lang/bindgen](https://github.com/rust-lang/rust-bindgen). - deny any direct field access to raw-bindgen structs and provide fully-accessible methods. - automatically handle *resource types* that need proper resource management (e.g. calling `mj_deleteModel` for `MjModel` in its `Drop` impl). -- Naming convention for MuJoCo items: - - *resource types*: PascalCase (`Mj~`) - - *other types*: as they are in MuJoCo (`mj~`) - - *functions*: as they in MuJoCo (`mj~_~`) ## Previous Works diff --git a/examples/visualize_left_object.rs b/examples/visualize_left_object.rs index ece3258..85e1566 100644 --- a/examples/visualize_left_object.rs +++ b/examples/visualize_left_object.rs @@ -1,5 +1,5 @@ use rusty_mujoco::{mj_loadXML, mj_makeData, mj_step, mjr_render, mjv_updateScene}; -use rusty_mujoco::{MjrContext, mjrRect, MjvScene, mjvCamera, mjvOption, mjtCatBit, mjtFontScale}; +use rusty_mujoco::{mjrContext, mjrRect, mjvScene, mjvCamera, mjvOption, mjtCatBit, mjtFontScale}; struct Args { xml_path: String, @@ -49,9 +49,9 @@ fn main() { window.set_close_polling(true); glfw::Context::make_current(&mut *window); - let con = MjrContext::new(&model, mjtFontScale::X150); + let con = mjrContext::new(&model, mjtFontScale::X150); let opt = mjvOption::default(); - let mut scn = MjvScene::new(&model, 2000); + let mut scn = mjvScene::new(&model, 2000); let mut cam = mjvCamera::default(); camera_name.map(|name| cam.set_fixedcamid(model.object_id(&name).expect("No camera of such name in the model"))); diff --git a/src/functions/assets.rs b/src/functions/assets.rs index fcbf300..5b92c3b 100644 --- a/src/functions/assets.rs +++ b/src/functions/assets.rs @@ -1,33 +1,33 @@ //! # [Assets](https://mujoco.readthedocs.io/en/stable/APIreference/APIfunctions.html#assets) -use crate::{MjSpec, mjsMesh, mjsDefault, mjsHField, mjsSkin, mjsTexture, mjsMaterial}; +use crate::{mjSpec, mjsMesh, mjsDefault, mjsHField, mjsSkin, mjsTexture, mjsMaterial}; /// Add mesh to mjSpec. pub fn mjs_addMesh<'spec>( - s: &'spec mut MjSpec, + s: &'spec mut mjSpec, def: &mjsDefault, ) -> &'spec mut mjsMesh { unsafe { &mut *crate::bindgen::mjs_addMesh(s.as_mut_ptr(), def) } } /// Add height field to mjSpec. -pub fn mjs_addHField<'spec>(s: &'spec mut MjSpec) -> &'spec mut mjsHField { +pub fn mjs_addHField<'spec>(s: &'spec mut mjSpec) -> &'spec mut mjsHField { unsafe { &mut *crate::bindgen::mjs_addHField(s.as_mut_ptr()) } } /// Add skin to mjSpec. -pub fn mjs_addSkin<'spec>(s: &'spec mut MjSpec) -> &'spec mut mjsSkin { +pub fn mjs_addSkin<'spec>(s: &'spec mut mjSpec) -> &'spec mut mjsSkin { unsafe { &mut *crate::bindgen::mjs_addSkin(s.as_mut_ptr()) } } /// Add texture to mjSpec. -pub fn mjs_addTexture<'spec>(s: &'spec mut MjSpec) -> &'spec mut mjsTexture { +pub fn mjs_addTexture<'spec>(s: &'spec mut mjSpec) -> &'spec mut mjsTexture { unsafe { &mut *crate::bindgen::mjs_addTexture(s.as_mut_ptr()) } } /// Add material to mjSpec. pub fn mjs_addMaterial<'spec>( - s: &'spec mut MjSpec, + s: &'spec mut mjSpec, def: &mjsDefault, ) -> &'spec mut mjsMaterial { unsafe { &mut *crate::bindgen::mjs_addMaterial(s.as_mut_ptr(), def) } diff --git a/src/functions/attachment.rs b/src/functions/attachment.rs index 6f3505e..445ddb1 100644 --- a/src/functions/attachment.rs +++ b/src/functions/attachment.rs @@ -1,6 +1,6 @@ //! # [Attachment](https://mujoco.readthedocs.io/en/stable/APIreference/APIfunctions.html#attachment) -use crate::{MjSpec, mjsElement, mjsBody, mjsDefault}; +use crate::{mjSpec, mjsElement, mjsBody, mjsDefault}; /// Attach child to a parent, return the attached element if success or `None` otherwise. /* mjsElement* mjs_attach(mjsElement* parent, const mjsElement* child, @@ -28,7 +28,7 @@ pub fn mjs_attach<'element>( /// Delete body and descendants from mjSpec, remove all references. /* int mjs_detachBody(mjSpec* s, mjsBody* b); */ -pub fn mjs_detachBody(s: &mut MjSpec, b: &mut mjsBody) -> Result<(), ()> { +pub fn mjs_detachBody(s: &mut mjSpec, b: &mut mjsBody) -> Result<(), ()> { /* > return 0 on success @@ -38,7 +38,7 @@ pub fn mjs_detachBody(s: &mut MjSpec, b: &mut mjsBody) -> Result<(), ()> { /// Delete default class and descendants from mjSpec, remove all references. /* int mjs_detachDefault(mjSpec* s, mjsDefault* d); */ -pub fn mjs_detachDefault(s: &mut MjSpec, d: &mut mjsDefault) -> Result<(), ()> { +pub fn mjs_detachDefault(s: &mut mjSpec, d: &mut mjsDefault) -> Result<(), ()> { /* > return 0 on success diff --git a/src/functions/components.rs b/src/functions/components.rs index 266f027..f58ae72 100644 --- a/src/functions/components.rs +++ b/src/functions/components.rs @@ -4,72 +4,72 @@ /// Run position-dependent computations. /* void mj_fwdPosition(const mjModel* m, mjData* d); */ -pub fn mj_fwdPosition(m: &crate::MjModel, d: &mut crate::MjData) { +pub fn mj_fwdPosition(m: &crate::mjModel, d: &mut crate::mjData) { unsafe { crate::bindgen::mj_fwdPosition(m.as_ptr(), d.as_mut_ptr()) } } /// Run velocity-dependent computations. /* void mj_fwdVelocity(const mjModel* m, mjData* d); */ -pub fn mj_fwdVelocity(m: &crate::MjModel, d: &mut crate::MjData) { +pub fn mj_fwdVelocity(m: &crate::mjModel, d: &mut crate::mjData) { unsafe { crate::bindgen::mj_fwdVelocity(m.as_ptr(), d.as_mut_ptr()) } } /// Compute actuator force qfrc_actuator. /* void mj_fwdActuation(const mjModel* m, mjData* d); */ -pub fn mj_fwdActuation(m: &crate::MjModel, d: &mut crate::MjData) { +pub fn mj_fwdActuation(m: &crate::mjModel, d: &mut crate::mjData) { unsafe { crate::bindgen::mj_fwdActuation(m.as_ptr(), d.as_mut_ptr()) } } /// Add up all non-constraint forces, compute qacc_smooth. /* void mj_fwdAcceleration(const mjModel* m, mjData* d); */ -pub fn mj_fwdAcceleration(m: &crate::MjModel, d: &mut crate::MjData) { +pub fn mj_fwdAcceleration(m: &crate::mjModel, d: &mut crate::mjData) { unsafe { crate::bindgen::mj_fwdAcceleration(m.as_ptr(), d.as_mut_ptr()) } } /// Run selected constraint solver. /* void mj_fwdConstraint(const mjModel* m, mjData* d); */ -pub fn mj_fwdConstraint(m: &crate::MjModel, d: &mut crate::MjData) { +pub fn mj_fwdConstraint(m: &crate::mjModel, d: &mut crate::mjData) { unsafe { crate::bindgen::mj_fwdConstraint(m.as_ptr(), d.as_mut_ptr()) } } /// Euler integrator, semi-implicit in velocity. /* void mj_Euler(const mjModel* m, mjData* d); */ -pub fn mj_Euler(m: &crate::MjModel, d: &mut crate::MjData) { +pub fn mj_Euler(m: &crate::mjModel, d: &mut crate::mjData) { unsafe { crate::bindgen::mj_Euler(m.as_ptr(), d.as_mut_ptr()) } } /// Runge-Kutta explicit order-N integrator. /* void mj_RungeKutta(const mjModel* m, mjData* d, int N); */ -pub fn mj_RungeKutta(m: &crate::MjModel, d: &mut crate::MjData, n: usize) { +pub fn mj_RungeKutta(m: &crate::mjModel, d: &mut crate::mjData, n: usize) { unsafe { crate::bindgen::mj_RungeKutta(m.as_ptr(), d.as_mut_ptr(), n as i32) } } /// Integrates the simulation state using an implicit-in-velocity integrator (either “implicit” or “implicitfast”, see Numerical Integration), and advances simulation time. See mjdata.h for fields computed by this function. /* void mj_implicit(const mjModel* m, mjData* d); */ -pub fn mj_implicit(m: &crate::MjModel, d: &mut crate::MjData) { +pub fn mj_implicit(m: &crate::mjModel, d: &mut crate::mjData) { unsafe { crate::bindgen::mj_implicit(m.as_ptr(), d.as_mut_ptr()) } } /// Run position-dependent computations in inverse dynamics. /* void mj_invPosition(const mjModel* m, mjData* d); */ -pub fn mj_invPosition(m: &crate::MjModel, d: &mut crate::MjData) { +pub fn mj_invPosition(m: &crate::mjModel, d: &mut crate::mjData) { unsafe { crate::bindgen::mj_invPosition(m.as_ptr(), d.as_mut_ptr()) } } /// Run velocity-dependent computations in inverse dynamics. /* void mj_invVelocity(const mjModel* m, mjData* d); */ -pub fn mj_invVelocity(m: &crate::MjModel, d: &mut crate::MjData) { +pub fn mj_invVelocity(m: &crate::mjModel, d: &mut crate::mjData) { unsafe { crate::bindgen::mj_invVelocity(m.as_ptr(), d.as_mut_ptr()) } } /// Apply the analytical formula for inverse constraint dynamics. /* void mj_invConstraint(const mjModel* m, mjData* d); */ -pub fn mj_invConstraint(m: &crate::MjModel, d: &mut crate::MjData) { +pub fn mj_invConstraint(m: &crate::mjModel, d: &mut crate::mjData) { unsafe { crate::bindgen::mj_invConstraint(m.as_ptr(), d.as_mut_ptr()) } } /// Compare forward and inverse dynamics, save results in fwdinv. /* void mj_compareFwdInv(const mjModel* m, mjData* d); */ -pub fn mj_compareFwdInv(m: &crate::MjModel, d: &mut crate::MjData) { +pub fn mj_compareFwdInv(m: &crate::mjModel, d: &mut crate::mjData) { unsafe { crate::bindgen::mj_compareFwdInv(m.as_ptr(), d.as_mut_ptr()) } } diff --git a/src/functions/element_initialization.rs b/src/functions/element_initialization.rs index 54b88f1..a4dad42 100644 --- a/src/functions/element_initialization.rs +++ b/src/functions/element_initialization.rs @@ -1,7 +1,7 @@ //! # [Element initialization](https://mujoco.readthedocs.io/en/stable/APIreference/APIfunctions.html#element-initialization) use crate::{ - MjSpec, + mjSpec, mjsOrientation, mjsBody, mjsFrame, mjsJoint, mjsGeom, mjsSite, mjsCamera, mjsLight, mjsFlex, mjsMesh, mjsHField, mjsSkin, mjsTexture, mjsMaterial, mjsPair, mjsEquality, mjsTendon, @@ -13,10 +13,10 @@ use crate::{ /// /// **note**: This function is called in the `Default` implementation of [`mjSpec`]. /* void mjs_defaultSpec(mjSpec* spec); */ -pub fn mjs_defaultSpec() -> MjSpec { +pub fn mjs_defaultSpec() -> mjSpec { let mut c = Box::::new_uninit(); unsafe { crate::bindgen::mjs_defaultSpec(c.as_mut_ptr()); } - MjSpec::from_raw(Box::into_raw(unsafe { c.assume_init() })) + mjSpec::from_raw(Box::into_raw(unsafe { c.assume_init() })) } /// Set default orientation attributes. diff --git a/src/functions/error_and_memory.rs b/src/functions/error_and_memory.rs index b437117..c6d4330 100644 --- a/src/functions/error_and_memory.rs +++ b/src/functions/error_and_memory.rs @@ -37,7 +37,7 @@ pub fn mju_free(ptr: *mut u8) { /// High-level warning function: count warnings in mjData, print only the first. /* void mj_warning(mjData* d, int warning, int info); */ pub fn mj_warning( - d: &mut crate::MjData, + d: &mut crate::mjData, warning: crate::bindgen::mjtWarning, info: usize, ) { @@ -54,7 +54,7 @@ pub fn mju_writeLog(kind: impl Into, msg: impl Into) { /// Get compiler error message from spec. /* const char* mjs_getError(mjSpec* s); */ -pub fn mjs_getError(s: &mut crate::MjSpec) -> Option { +pub fn mjs_getError(s: &mut crate::mjSpec) -> Option { let c_ptr = unsafe { crate::bindgen::mjs_getError(s.as_mut_ptr()) }; if c_ptr.is_null() { None @@ -65,7 +65,7 @@ pub fn mjs_getError(s: &mut crate::MjSpec) -> Option { /// Check if compiler error is a warning. /* int mjs_isWarning(mjSpec* s); */ -pub fn mjs_isWarning(s: &mut crate::MjSpec) -> bool { +pub fn mjs_isWarning(s: &mut crate::mjSpec) -> bool { /* > Returns 1 if the error is a warning. diff --git a/src/functions/find_and_get_utilities.rs b/src/functions/find_and_get_utilities.rs index 6c2a8d3..2b0d7d2 100644 --- a/src/functions/find_and_get_utilities.rs +++ b/src/functions/find_and_get_utilities.rs @@ -1,29 +1,29 @@ //! # [Find and get utilities](https://mujoco.readthedocs.io/en/stable/APIreference/APIfunctions.html#find-and-get-utilities) use crate::{ - MjSpec, + mjSpec, mjsElement, mjsBody, mjsFrame, mjsDefault, mjtObj, }; /// Get spec from element. /* mjSpec* mjs_getSpec(mjsElement* element); */ -pub fn mjs_getSpec(element: &mut mjsElement) -> Option { +pub fn mjs_getSpec(element: &mut mjsElement) -> Option { let ptr = unsafe { crate::bindgen::mjs_getSpec(element) }; - if ptr.is_null() {None} else {Some(MjSpec::from_raw(ptr)) } + if ptr.is_null() {None} else {Some(mjSpec::from_raw(ptr)) } } /// Find spec (model asset) by name. /* mjSpec* mjs_findSpec(mjSpec* spec, const char* name); */ -pub fn mjs_findSpec<'spec>(spec: &'spec mut MjSpec, name: &str) -> Option { +pub fn mjs_findSpec<'spec>(spec: &'spec mut mjSpec, name: &str) -> Option { let name = std::ffi::CString::new(name).expect("`name` must not contain null bytes"); let ptr = unsafe { crate::bindgen::mjs_findSpec(spec.as_mut_ptr(), name.as_ptr()) }; - if ptr.is_null() {None} else {Some(MjSpec::from_raw(ptr)) } + if ptr.is_null() {None} else {Some(mjSpec::from_raw(ptr)) } } /// Find body in spec by name. /* mjsBody* mjs_findBody(mjSpec* s, const char* name); */ -pub fn mjs_findBody<'spec>(spec: &'spec mut MjSpec, name: &str) -> Option<&'spec mut mjsBody> { +pub fn mjs_findBody<'spec>(spec: &'spec mut mjSpec, name: &str) -> Option<&'spec mut mjsBody> { let name = std::ffi::CString::new(name).expect("`name` must not contain null bytes"); let ptr = unsafe { crate::bindgen::mjs_findBody(spec.as_mut_ptr(), name.as_ptr()) }; if ptr.is_null() {None} else {Some(unsafe { &mut *ptr }) } @@ -32,7 +32,7 @@ pub fn mjs_findBody<'spec>(spec: &'spec mut MjSpec, name: &str) -> Option<&'spec /// Find element in spec by name. /* mjsElement* mjs_findElement(mjSpec* s, mjtObj type, const char* name); */ pub fn mjs_findElement<'spec>( - spec: &'spec mut MjSpec, + spec: &'spec mut mjSpec, type_: mjtObj, name: &str, ) -> Option<&'spec mut mjsElement> { @@ -65,7 +65,7 @@ pub fn mjs_getFrame<'element>(element: &'element mut mjsElement) -> Option<&'ele /// Find frame by name. /* mjsFrame* mjs_findFrame(mjSpec* s, const char* name); */ -pub fn mjs_findFrame<'spec>(spec: &'spec mut MjSpec, name: &str) -> Option<&'spec mut mjsFrame> { +pub fn mjs_findFrame<'spec>(spec: &'spec mut mjSpec, name: &str) -> Option<&'spec mut mjsFrame> { let name = std::ffi::CString::new(name).expect("`name` must not contain null bytes"); let ptr = unsafe { crate::bindgen::mjs_findFrame(spec.as_mut_ptr(), name.as_ptr()) }; if ptr.is_null() {None} else {Some(unsafe { &mut *ptr }) } @@ -81,7 +81,7 @@ pub fn mjs_getDefault<'element>(element: &'element mut mjsElement) -> Option<&'e /// Find default in model by class name. /* mjsDefault* mjs_findDefault(mjSpec* s, const char* classname); */ pub fn mjs_findDefault<'spec>( - spec: &'spec mut MjSpec, + spec: &'spec mut mjSpec, classname: &str, ) -> Option<&'spec mut mjsDefault> { let classname = std::ffi::CString::new(classname).expect("`classname` must not contain null bytes"); @@ -91,7 +91,7 @@ pub fn mjs_findDefault<'spec>( /// Get global default from model. /* mjsDefault* mjs_getSpecDefault(mjSpec* s); */ -pub fn mjs_getSpecDefault<'spec>(spec: &'spec mut MjSpec) -> Option<&'spec mut mjsDefault> { +pub fn mjs_getSpecDefault<'spec>(spec: &'spec mut mjSpec) -> Option<&'spec mut mjsDefault> { let ptr = unsafe { crate::bindgen::mjs_getSpecDefault(spec.as_mut_ptr()) }; if ptr.is_null() {None} else {Some(unsafe { &mut *ptr })} } @@ -127,7 +127,7 @@ pub fn mjs_nextChild<'body>( /// Return spec’s first element of selected type. /* mjsElement* mjs_firstElement(mjSpec* s, mjtObj type); */ pub fn mjs_firstElement<'spec>( - spec: &'spec mut MjSpec, + spec: &'spec mut mjSpec, type_: mjtObj, ) -> Option<&'spec mut mjsElement> { let ptr = unsafe { crate::bindgen::mjs_firstElement(spec.as_mut_ptr(), type_) }; @@ -137,7 +137,7 @@ pub fn mjs_firstElement<'spec>( /// Return spec’s next element; return `None` if element is last. /* mjsElement* mjs_nextElement(mjSpec* s, mjsElement* element); */ pub fn mjs_nextElement<'spec>( - spec: &'spec mut MjSpec, + spec: &'spec mut mjSpec, element: &mut mjsElement, ) -> Option<&'spec mut mjsElement> { let ptr = unsafe { crate::bindgen::mjs_nextElement(spec.as_mut_ptr(), element) }; diff --git a/src/functions/initialization.rs b/src/functions/initialization.rs index f8b58bb..a8b6f96 100644 --- a/src/functions/initialization.rs +++ b/src/functions/initialization.rs @@ -57,7 +57,7 @@ pub fn mj_defaultVisual() -> crate::mjVisual { /// (e.g. same `nq`, `nv`, `nbody`, ...) /// /* mjModel* mj_copyModel(mjModel* dest, const mjModel* src); */ -pub unsafe fn mj_copyModel(dest: Option<&mut crate::MjModel>, src: &crate::MjModel) -> Option { +pub unsafe fn mj_copyModel(dest: Option<&mut crate::mjModel>, src: &crate::mjModel) -> Option { match dest { Some(dest) => { unsafe { crate::bindgen::mj_copyModel(dest.as_mut_ptr(), src.as_ptr()) }; @@ -66,7 +66,7 @@ pub unsafe fn mj_copyModel(dest: Option<&mut crate::MjModel>, src: &crate::MjMod None => { let ptr = std::ptr::null_mut(); unsafe { crate::bindgen::mj_copyModel(ptr, src.as_ptr()); } - Some(crate::MjModel::from_raw(ptr)) + Some(crate::mjModel::from_raw(ptr)) } } } @@ -76,7 +76,7 @@ pub unsafe fn mj_copyModel(dest: Option<&mut crate::MjModel>, src: &crate::MjMod /// The size of the buffer must be at least `mj_sizeModel(m)`. /* void mj_saveModel(const mjModel* m, const char* filename, void* buffer, int buffer_sz); */ pub fn mj_saveModel( - m: &crate::MjModel, + m: &crate::mjModel, filename: Option>, buffer: Option<&mut [u8]>, ) { @@ -96,7 +96,7 @@ pub fn mj_saveModel( /* mjModel* mj_loadModel(const char* filename, const mjVFS* vfs); */ pub fn mj_loadModel( filename: impl Into, -) -> crate::MjModel { +) -> crate::mjModel { let filename = std::ffi::CString::new(filename.into()).unwrap(); let c_ptr = unsafe { crate::bindgen::mj_loadModel( @@ -107,32 +107,32 @@ pub fn mj_loadModel( #[cfg(debug_assertions)] { assert!(!c_ptr.is_null(), "Failed to load model from file: {}", filename.to_string_lossy()); } - crate::MjModel::from_raw(c_ptr) + crate::mjModel::from_raw(c_ptr) } /// Free memory allocation in model. /// -/// **note**: [`MjModel`](crate::MjModel) calls this function in its `Drop` implementation. +/// **note**: [`mjModel`](crate::mjModel) calls this function in its `Drop` implementation. /* void mj_deleteModel(mjModel* m); */ -pub fn mj_deleteModel(m: &mut crate::MjModel) { +pub fn mj_deleteModel(m: &mut crate::mjModel) { unsafe { crate::bindgen::mj_deleteModel(m.as_mut_ptr()); } } /// Return size of buffer needed to hold model. /* int mj_sizeModel(const mjModel* m); */ -pub fn mj_sizeModel(m: &crate::MjModel) -> usize { +pub fn mj_sizeModel(m: &crate::mjModel) -> usize { unsafe { crate::bindgen::mj_sizeModel(m.as_ptr()) as usize } } /// Allocate mjData corresponding to given model. If the model buffer is unallocated /// the initial configuration will not be set. /* mjData* mj_makeData(const mjModel* m); */ -pub fn mj_makeData(m: &crate::MjModel) -> crate::MjData { +pub fn mj_makeData(m: &crate::mjModel) -> crate::mjData { let c_ptr = unsafe { crate::bindgen::mj_makeData(m.as_ptr()) }; #[cfg(debug_assertions)] { assert!(!c_ptr.is_null(), "Failed to allocate mjData for model"); } - crate::MjData::from_raw(c_ptr) + crate::mjData::from_raw(c_ptr) } /// Copy mjData. `m` is only required to contain the size fields from MJMODEL_INTS. @@ -146,27 +146,27 @@ pub fn mj_makeData(m: &crate::MjModel) -> crate::MjData { /// (e.g. same `nq`, `nv`, `nbody`, ...) /// /* mjData* mj_copyData(mjData* dest, const mjModel* m, const mjData* src); */ -pub unsafe fn mj_copyData(dest: &mut crate::MjData, m: &crate::MjModel, src: &crate::MjData) { +pub unsafe fn mj_copyData(dest: &mut crate::mjData, m: &crate::mjModel, src: &crate::mjData) { unsafe { crate::bindgen::mj_copyData(dest.as_mut_ptr(), m.as_ptr(), src.as_ptr()) }; } /// Reset data to defaults. /* void mj_resetData(const mjModel* m, mjData* d); */ -pub fn mj_resetData(m: &crate::MjModel, d: &mut crate::MjData) { +pub fn mj_resetData(m: &crate::mjModel, d: &mut crate::mjData) { unsafe { crate::bindgen::mj_resetData(m.as_ptr(), d.as_mut_ptr()) } } /// Reset data to defaults, fill everything else with debug_value. /* void mj_resetDataDebug(const mjModel* m, mjData* d, unsigned char debug_value); */ -pub fn mj_resetDataDebug(m: &crate::MjModel, d: &mut crate::MjData, debug_value: u8) { +pub fn mj_resetDataDebug(m: &crate::mjModel, d: &mut crate::mjData, debug_value: u8) { unsafe { crate::bindgen::mj_resetDataDebug(m.as_ptr(), d.as_mut_ptr(), debug_value) } } /// Reset data. If `key` is given, set fields from specified keyframe. /* void mj_resetDataKeyframe(const mjModel* m, mjData* d, int key); */ pub fn mj_resetDataKeyframe( - m: &crate::MjModel, - d: &mut crate::MjData, + m: &crate::mjModel, + d: &mut crate::mjData, key: Option>, ) { unsafe { @@ -180,39 +180,39 @@ pub fn mj_resetDataKeyframe( /// Mark a new frame on the mjData stack. /* void mj_markStack(mjData* d); */ -pub fn mj_markStack(d: &mut crate::MjData) { +pub fn mj_markStack(d: &mut crate::mjData) { unsafe { crate::bindgen::mj_markStack(d.as_mut_ptr()) } } /// Free the current mjData stack frame. All pointers returned by `mj_stackAlloc` since the last call to `mj_markStack` must no longer be used afterwards. /* void mj_freeStack(mjData* d); */ -pub fn mj_freeStack(d: &mut crate::MjData) { +pub fn mj_freeStack(d: &mut crate::mjData) { unsafe { crate::bindgen::mj_freeStack(d.as_mut_ptr()) } } /// Allocate a number of bytes on mjData stack at a specific alignment. Call `mju_error` on stack overflow. /* void* mj_stackAllocByte(mjData* d, size_t bytes, size_t alignment); */ -pub fn mj_stackAllocByte(d: &mut crate::MjData, bytes: usize, alignment: usize) -> *mut u8 { +pub fn mj_stackAllocByte(d: &mut crate::mjData, bytes: usize, alignment: usize) -> *mut u8 { unsafe { crate::bindgen::mj_stackAllocByte(d.as_mut_ptr(), bytes, alignment) as *mut u8 } } /// Allocate array of `mjtNums` on mjData stack. Call `mju_error` on stack overflow. /* mjtNum* mj_stackAllocNum(mjData* d, size_t size); */ -pub fn mj_stackAllocNum(d: &mut crate::MjData, size: usize) -> *mut f64 { +pub fn mj_stackAllocNum(d: &mut crate::mjData, size: usize) -> *mut f64 { unsafe { crate::bindgen::mj_stackAllocNum(d.as_mut_ptr(), size) as *mut f64 } } /// Allocate array of `ints` on mjData stack. Call `mju_error` on stack overflow. /* int* mj_stackAllocInt(mjData* d, size_t size); */ -pub fn mj_stackAllocInt(d: &mut crate::MjData, size: usize) -> *mut i32 { +pub fn mj_stackAllocInt(d: &mut crate::mjData, size: usize) -> *mut i32 { unsafe { crate::bindgen::mj_stackAllocInt(d.as_mut_ptr(), size) as *mut i32 } } /// Free memory allocation in mjData. /// -/// **note**: [`MjData`](crate::MjData) calls this function in its `Drop` implementation. +/// **note**: [`mjData`](crate::mjData) calls this function in its `Drop` implementation. /* void mj_deleteData(mjData* d); */ -pub fn mj_deleteData(d: &mut crate::MjData) { +pub fn mj_deleteData(d: &mut crate::mjData) { unsafe { crate::bindgen::mj_deleteData(d.as_mut_ptr()) }; } @@ -224,7 +224,7 @@ pub fn mj_resetCallbacks() { /// Set constant fields of mjModel, corresponding to `qpos0` configuration. /* void mj_setConst(mjModel* m, mjData* d); */ -pub fn mj_setConst(m: &mut crate::MjModel, d: &mut crate::MjData) { +pub fn mj_setConst(m: &mut crate::mjModel, d: &mut crate::mjData) { unsafe { crate::bindgen::mj_setConst(m.as_mut_ptr(), d.as_mut_ptr()) }; } @@ -232,8 +232,8 @@ pub fn mj_setConst(m: &mut crate::MjModel, d: &mut crate::MjData) { /* int mj_setLengthRange(mjModel* m, mjData* d, int index, const mjLROpt* opt, char* error, int error_sz); */ pub fn mj_setLengthRange( - m: &mut crate::MjModel, - d: &mut crate::MjData, + m: &mut crate::mjModel, + d: &mut crate::mjData, index: ObjectId, opt: &crate::mjLROpt, ) -> Result<(), MjError> { @@ -265,38 +265,38 @@ pub fn mj_setLengthRange( /// /// **note**: [`mjSpec`] calls this function in its `Default` implementation. /* mjSpec* mj_makeSpec(void); */ -pub fn mj_makeSpec() -> crate::MjSpec { +pub fn mj_makeSpec() -> crate::mjSpec { let c_ptr = unsafe { crate::bindgen::mj_makeSpec() }; #[cfg(debug_assertions)] { assert!(!c_ptr.is_null(), "Failed to create empty mjSpec"); } - crate::MjSpec::from_raw(c_ptr) + crate::mjSpec::from_raw(c_ptr) } /// Copy spec. /// /// **note**: [`mjSpec`] calls this function in its `Clone` implementation. /* mjSpec* mj_copySpec(const mjSpec* s); */ -pub fn mj_copySpec(s: &crate::MjSpec) -> crate::MjSpec { +pub fn mj_copySpec(s: &crate::mjSpec) -> crate::mjSpec { let c_ptr = unsafe { crate::bindgen::mj_copySpec(s.as_ptr()) }; #[cfg(debug_assertions)] { assert!(!c_ptr.is_null(), "Failed to copy mjSpec"); } - crate::MjSpec::from_raw(c_ptr) + crate::mjSpec::from_raw(c_ptr) } /// Free memory allocation in mjSpec. /// /// **note**: [`mjSpec`] calls this function in its `Drop` implementation. /* void mj_deleteSpec(mjSpec* s); */ -pub fn mj_deleteSpec(s: &mut crate::MjSpec) { +pub fn mj_deleteSpec(s: &mut crate::mjSpec) { unsafe { crate::bindgen::mj_deleteSpec(s.as_mut_ptr()) }; drop(unsafe { Box::from_raw(s.as_mut_ptr()) }); } /// Activate plugin. /* int mjs_activatePlugin(mjSpec* s, const char* name); */ -pub fn mjs_activatePlugin(s: &mut crate::MjSpec, name: impl Into) -> Result<(), MjError> { +pub fn mjs_activatePlugin(s: &mut crate::mjSpec, name: impl Into) -> Result<(), MjError> { let name = std::ffi::CString::new(name.into()).unwrap(); let status = unsafe { crate::bindgen::mjs_activatePlugin(s.as_mut_ptr(), name.as_ptr()) }; @@ -313,7 +313,7 @@ pub fn mjs_activatePlugin(s: &mut crate::MjSpec, name: impl Into) -> Res /// Turn deep copy on or off attach. /* int mjs_setDeepCopy(mjSpec* s, int deepcopy); */ -pub fn mjs_setDeepCopy(s: &mut crate::MjSpec, deepcopy: bool) -> Result<(), MjError> { +pub fn mjs_setDeepCopy(s: &mut crate::mjSpec, deepcopy: bool) -> Result<(), MjError> { let status = unsafe { crate::bindgen::mjs_setDeepCopy(s.as_mut_ptr(), deepcopy as i32) }; /* diff --git a/src/functions/interaction.rs b/src/functions/interaction.rs index c6369f3..013845e 100644 --- a/src/functions/interaction.rs +++ b/src/functions/interaction.rs @@ -3,7 +3,7 @@ //! These functions implement abstract mouse interactions, allowing control over cameras and perturbations. //! Their use is well illustrated in [simulate](https://mujoco.readthedocs.io/en/stable/programming/samples.html#sasimulate). -use crate::{MjModel, MjData, MjvScene, mjvCamera, mjvGLCamera, mjvPerturb, mjvOption}; +use crate::{mjModel, mjData, mjvScene, mjvCamera, mjvGLCamera, mjvPerturb, mjvOption}; use crate::{ObjectId, obj}; /// Set default camera. @@ -18,7 +18,7 @@ pub fn mjv_defaultCamera() -> mjvCamera { /// Set default free camera. /* void mjv_defaultFreeCamera(const mjModel* m, mjvCamera* cam); */ -pub fn mjv_defaultFreeCamera(m: &MjModel) -> mjvCamera { +pub fn mjv_defaultFreeCamera(m: &mjModel) -> mjvCamera { let mut cam = std::mem::MaybeUninit::::uninit(); unsafe { crate::bindgen::mjv_defaultFreeCamera(m.as_ptr(), cam.as_mut_ptr()) }; unsafe { cam.assume_init() } @@ -41,7 +41,7 @@ pub fn mjv_defaultPerturb() -> mjvPerturb { pub fn mjv_room2model( roompos: [f64; 3], roomquat: [f64; 4], - scn: &MjvScene, + scn: &mjvScene, ) -> ([f64; 3], [f64; 4]) { let mut modelpos = [0.0; 3]; let mut modelquat = [0.0; 4]; @@ -66,7 +66,7 @@ pub fn mjv_room2model( pub fn mjv_model2room( modelpos: [f64; 3], modelquat: [f64; 4], - scn: &MjvScene, + scn: &mjvScene, ) -> ([f64; 3], [f64; 4]) { let mut roompos = [0.0; 3]; let mut roomquat = [0.0; 4]; @@ -88,7 +88,7 @@ pub fn mjv_model2room( /// returning `(headpos, forward, up)`. /* void mjv_cameraInModel(mjtNum headpos[3], mjtNum forward[3], mjtNum up[3], const mjvScene* scn); */ -pub fn mjv_cameraInModel(scn: &MjvScene) -> ([f64; 3], [f64; 3], [f64; 3]) { +pub fn mjv_cameraInModel(scn: &mjvScene) -> ([f64; 3], [f64; 3], [f64; 3]) { let mut headpos = [0.0; 3]; let mut forward = [0.0; 3]; let mut up = [0.0; 3]; @@ -109,7 +109,7 @@ pub fn mjv_cameraInModel(scn: &MjvScene) -> ([f64; 3], [f64; 3], [f64; 3]) { /// returning `(headpos, forward, up)`. /* void mjv_cameraInRoom(mjtNum headpos[3], mjtNum forward[3], mjtNum up[3], const mjvScene* scn); */ -pub fn mjv_cameraInRoom(scn: &MjvScene) -> ([f64; 3], [f64; 3], [f64; 3]) { +pub fn mjv_cameraInRoom(scn: &mjvScene) -> ([f64; 3], [f64; 3], [f64; 3]) { let mut headpos = [0.0; 3]; let mut forward = [0.0; 3]; let mut up = [0.0; 3]; @@ -128,7 +128,7 @@ pub fn mjv_cameraInRoom(scn: &MjvScene) -> ([f64; 3], [f64; 3], [f64; 3]) { /// Get frustum height at unit distance from camera; average left and right OpenGL cameras. /* mjtNum mjv_frustumHeight(const mjvScene* scn); */ -pub fn mjv_frustumHeight(scn: &MjvScene) -> f64 { +pub fn mjv_frustumHeight(scn: &mjvScene) -> f64 { unsafe { crate::bindgen::mjv_frustumHeight(scn.as_ptr()) } } @@ -150,11 +150,11 @@ pub fn mjv_alignToCamera(vec: [f64; 3], forward: [f64; 3]) -> [f64; 3] { /* void mjv_moveCamera(const mjModel* m, int action, mjtNum reldx, mjtNum reldy, const mjvScene* scn, mjvCamera* cam); */ pub fn mjv_moveCamera( - m: &MjModel, + m: &mjModel, action: crate::bindgen::mjtMouse, reldx: f64, reldy: f64, - scn: &MjvScene, + scn: &mjvScene, cam: &mut mjvCamera, ) { unsafe { @@ -173,12 +173,12 @@ pub fn mjv_moveCamera( /* void mjv_movePerturb(const mjModel* m, const mjData* d, int action, mjtNum reldx, mjtNum reldy, const mjvScene* scn, mjvPerturb* pert); */ pub fn mjv_movePerturb( - m: &MjModel, - d: &MjData, + m: &mjModel, + d: &mjData, action: crate::bindgen::mjtMouse, reldx: f64, reldy: f64, - scn: &MjvScene, + scn: &mjvScene, pert: &mut mjvPerturb, ) { unsafe { @@ -198,12 +198,12 @@ pub fn mjv_movePerturb( /* void mjv_moveModel(const mjModel* m, int action, mjtNum reldx, mjtNum reldy, const mjtNum roomup[3], mjvScene* scn); */ pub fn mjv_moveModel( - m: &MjModel, + m: &mjModel, action: crate::bindgen::mjtMouse, reldx: f64, reldy: f64, roomup: [f64; 3], - scn: &mut MjvScene, + scn: &mut mjvScene, ) { unsafe { crate::bindgen::mjv_moveModel( @@ -219,7 +219,7 @@ pub fn mjv_moveModel( /// Copy perturb pos,quat from selected body; set scale for perturbation. /* void mjv_initPerturb(const mjModel* m, mjData* d, const mjvScene* scn, mjvPerturb* pert); */ -pub fn mjv_initPerturb(m: &MjModel, d: &mut MjData, scn: &MjvScene, pert: &mut mjvPerturb) { +pub fn mjv_initPerturb(m: &mjModel, d: &mut mjData, scn: &mjvScene, pert: &mut mjvPerturb) { unsafe { crate::bindgen::mjv_initPerturb(m.as_ptr(), d.as_mut_ptr(), scn.as_ptr(), pert); } @@ -230,8 +230,8 @@ pub fn mjv_initPerturb(m: &MjModel, d: &mut MjData, scn: &MjvScene, pert: &mut m /* void mjv_applyPerturbPose(const mjModel* m, mjData* d, const mjvPerturb* pert, int flg_paused); */ pub fn mjv_applyPerturbPose( - m: &MjModel, - d: &mut MjData, + m: &mjModel, + d: &mut mjData, pert: &mjvPerturb, flg_paused: bool, ) { @@ -247,7 +247,7 @@ pub fn mjv_applyPerturbPose( /// Set perturb force,torque in d->xfrc_applied, if selected body is dynamic. /* void mjv_applyPerturbForce(const mjModel* m, mjData* d, const mjvPerturb* pert); */ -pub fn mjv_applyPerturbForce(m: &MjModel, d: &mut MjData, pert: &mjvPerturb) { +pub fn mjv_applyPerturbForce(m: &mjModel, d: &mut mjData, pert: &mjvPerturb) { unsafe { crate::bindgen::mjv_applyPerturbForce(m.as_ptr(), d.as_mut_ptr(), pert); } @@ -292,13 +292,13 @@ mod mjv_select { const mjvScene* scn, mjtNum selpnt[3], int geomid[1], int flexid[1], int skinid[1]); */ pub fn mjv_select( - m: &MjModel, - d: &MjData, + m: &mjModel, + d: &mjData, vopt: &mjvOption, aspectratio: f64, relx: f64, rely: f64, - scn: &MjvScene, + scn: &mjvScene, ) -> mjv_select::SelectResult { let mut geomid = [-1]; let mut flexid = [-1]; diff --git a/src/functions/main_simulation.rs b/src/functions/main_simulation.rs index cd7bdab..adecea7 100644 --- a/src/functions/main_simulation.rs +++ b/src/functions/main_simulation.rs @@ -8,37 +8,37 @@ //! //! The skip version of `mj_forward` and `mj_inverse` are useful for example when qpos was unchanged but qvel was changed (usually in the context of finite differencing). Then there is no point repeating the computations that only depend on qpos. Calling the dynamics with skipstage = mjSTAGE_POS will achieve these savings. -use crate::{MjModel, MjData}; +use crate::{mjModel, mjData}; /// Advance simulation, use control callback to obtain external force and control. -pub fn mj_step(m: &MjModel, d: &mut MjData) { +pub fn mj_step(m: &mjModel, d: &mut mjData) { unsafe { crate::bindgen::mj_step(m.as_ptr(), d.as_mut_ptr()) } } /// Advance simulation in two steps: before external force and control is set by user. -pub fn mj_step1(m: &MjModel, d: &mut MjData) { +pub fn mj_step1(m: &mjModel, d: &mut mjData) { unsafe { crate::bindgen::mj_step1(m.as_ptr(), d.as_mut_ptr()) } } /// Advance simulation in two steps: after external force and control is set by user. -pub fn mj_step2(m: &MjModel, d: &mut MjData) { +pub fn mj_step2(m: &mjModel, d: &mut mjData) { unsafe { crate::bindgen::mj_step2(m.as_ptr(), d.as_mut_ptr()) } } /// Forward dynamics: same as mj_step but do not integrate in time. -pub fn mj_forward(m: &MjModel, d: &mut MjData) { +pub fn mj_forward(m: &mjModel, d: &mut mjData) { unsafe { crate::bindgen::mj_forward(m.as_ptr(), d.as_mut_ptr()) } } /// Inverse dynamics: qacc must be set before calling. -pub fn mj_inverse(m: &MjModel, d: &mut MjData) { +pub fn mj_inverse(m: &mjModel, d: &mut mjData) { unsafe { crate::bindgen::mj_inverse(m.as_ptr(), d.as_mut_ptr()) } } /// Forward dynamics with skip pub fn mj_forwardSkip( - m: &MjModel, - d: &mut MjData, + m: &mjModel, + d: &mut mjData, skipstage: crate::bindgen::mjtStage, skipsensor: bool, ) { @@ -53,8 +53,8 @@ pub fn mj_forwardSkip( /// Inverse dynamics with skip pub fn mj_inverseSkip( - m: &MjModel, - d: &mut MjData, + m: &mjModel, + d: &mut mjData, skipstage: crate::bindgen::mjtStage, skipsensor: bool, ) { diff --git a/src/functions/non_tree_elements.rs b/src/functions/non_tree_elements.rs index 19113ff..881a6b6 100644 --- a/src/functions/non_tree_elements.rs +++ b/src/functions/non_tree_elements.rs @@ -1,11 +1,11 @@ //! # [Non-tree elements](https://mujoco.readthedocs.io/en/stable/APIreference/APIfunctions.html#non-tree-elements) -use crate::{MjSpec, mjsActuator, mjsDefault, mjsSensor, mjsFlex, mjsPair, mjsExclude, mjsEquality, mjsTendon, mjsWrap, mjsNumeric, mjsText, mjsTuple, mjsKey, mjsPlugin}; +use crate::{mjSpec, mjsActuator, mjsDefault, mjsSensor, mjsFlex, mjsPair, mjsExclude, mjsEquality, mjsTendon, mjsWrap, mjsNumeric, mjsText, mjsTuple, mjsKey, mjsPlugin}; /// Add actuator to mjSpec, return actuator spec. /* mjsActuator* mjs_addActuator(mjSpec* s, const mjsDefault* def); */ pub fn mjs_addActuator<'spec>( - s: &'spec mut MjSpec, + s: &'spec mut mjSpec, def: &mjsDefault, ) -> &'spec mut mjsActuator { unsafe { &mut *crate::bindgen::mjs_addActuator(s.as_mut_ptr(), def) } @@ -13,20 +13,20 @@ pub fn mjs_addActuator<'spec>( /// Add sensor to mjSpec, return sensor spec. /* mjsSensor* mjs_addSensor(mjSpec* s); */ -pub fn mjs_addSensor<'spec>(s: &'spec mut MjSpec) -> &'spec mut mjsSensor { +pub fn mjs_addSensor<'spec>(s: &'spec mut mjSpec) -> &'spec mut mjsSensor { unsafe { &mut *crate::bindgen::mjs_addSensor(s.as_mut_ptr()) } } /// Add flex to mjSpec, return flex spec. /* mjsFlex* mjs_addFlex(mjSpec* s); */ -pub fn mjs_addFlex<'spec>(s: &'spec mut MjSpec) -> &'spec mut mjsFlex { +pub fn mjs_addFlex<'spec>(s: &'spec mut mjSpec) -> &'spec mut mjsFlex { unsafe { &mut *crate::bindgen::mjs_addFlex(s.as_mut_ptr()) } } /// Add contact pair to mjSpec, return pair spec. /* mjsPair* mjs_addPair(mjSpec* s, const mjsDefault* def); */ pub fn mjs_addPair<'spec>( - s: &'spec mut MjSpec, + s: &'spec mut mjSpec, def: &mjsDefault, ) -> &'spec mut mjsPair { unsafe { &mut *crate::bindgen::mjs_addPair(s.as_mut_ptr(), def) } @@ -34,14 +34,14 @@ pub fn mjs_addPair<'spec>( /// Add excluded body pair to mjSpec, return exclude spec. /* mjsExclude* mjs_addExclude(mjSpec* s); */ -pub fn mjs_addExclude<'spec>(s: &'spec mut MjSpec) -> &'spec mut mjsExclude { +pub fn mjs_addExclude<'spec>(s: &'spec mut mjSpec) -> &'spec mut mjsExclude { unsafe { &mut *crate::bindgen::mjs_addExclude(s.as_mut_ptr()) } } /// Add equality to mjSpec, return equality spec. /* mjsEquality* mjs_addEquality(mjSpec* s, const mjsDefault* def); */ pub fn mjs_addEquality<'spec>( - s: &'spec mut MjSpec, + s: &'spec mut mjSpec, def: &mjsDefault, ) -> &'spec mut mjsEquality { unsafe { &mut *crate::bindgen::mjs_addEquality(s.as_mut_ptr(), def) } @@ -50,7 +50,7 @@ pub fn mjs_addEquality<'spec>( /// Add tendon to mjSpec, return tendon spec. /* mjsTendon* mjs_addTendon(mjSpec* s, const mjsDefault* def); */ pub fn mjs_addTendon<'spec>( - s: &'spec mut MjSpec, + s: &'spec mut mjSpec, def: &mjsDefault, ) -> &'spec mut mjsTendon { unsafe { &mut *crate::bindgen::mjs_addTendon(s.as_mut_ptr(), def) } @@ -100,38 +100,38 @@ pub fn mjs_wrapPulley<'tendon>( /// Add numeric to mjSpec, return numeric spec. /* mjsNumeric* mjs_addNumeric(mjSpec* s); */ -pub fn mjs_addNumeric<'spec>(s: &'spec mut MjSpec) -> &'spec mut mjsNumeric { +pub fn mjs_addNumeric<'spec>(s: &'spec mut mjSpec) -> &'spec mut mjsNumeric { unsafe { &mut *crate::bindgen::mjs_addNumeric(s.as_mut_ptr()) } } /// Add text to mjSpec, return text spec. /* mjsText* mjs_addText(mjSpec* s); */ -pub fn mjs_addText<'spec>(s: &'spec mut MjSpec) -> &'spec mut mjsText { +pub fn mjs_addText<'spec>(s: &'spec mut mjSpec) -> &'spec mut mjsText { unsafe { &mut *crate::bindgen::mjs_addText(s.as_mut_ptr()) } } /// Add tuple to mjSpec, return tuple spec. /* mjsTuple* mjs_addTuple(mjSpec* s); */ -pub fn mjs_addTuple<'spec>(s: &'spec mut MjSpec) -> &'spec mut mjsTuple { +pub fn mjs_addTuple<'spec>(s: &'spec mut mjSpec) -> &'spec mut mjsTuple { unsafe { &mut *crate::bindgen::mjs_addTuple(s.as_mut_ptr()) } } /// Add keyframe to mjSpec, return key spec. /* mjsKey* mjs_addKey(mjSpec* s); */ -pub fn mjs_addKey<'spec>(s: &'spec mut MjSpec) -> &'spec mut mjsKey { +pub fn mjs_addKey<'spec>(s: &'spec mut mjSpec) -> &'spec mut mjsKey { unsafe { &mut *crate::bindgen::mjs_addKey(s.as_mut_ptr()) } } /// Add plugin to mjSpec, return plugin spec. /* mjsPlugin* mjs_addPlugin(mjSpec* s); */ -pub fn mjs_addPlugin<'spec>(s: &'spec mut MjSpec) -> &'spec mut mjsPlugin { +pub fn mjs_addPlugin<'spec>(s: &'spec mut mjSpec) -> &'spec mut mjsPlugin { unsafe { &mut *crate::bindgen::mjs_addPlugin(s.as_mut_ptr()) } } /// Add default to mjSpec, return default spec. /* mjsDefault* mjs_addDefault(mjSpec* s, const char* classname, const mjsDefault* parent); */ pub fn mjs_addDefault<'spec>( - s: &'spec mut MjSpec, + s: &'spec mut mjSpec, classname: &str, parent: &mjsDefault, ) -> &'spec mut mjsDefault { diff --git a/src/functions/opengl_rendering.rs b/src/functions/opengl_rendering.rs index 976765a..b2f6c26 100644 --- a/src/functions/opengl_rendering.rs +++ b/src/functions/opengl_rendering.rs @@ -13,25 +13,25 @@ use crate::helper::{ }; use crate::{ ObjectId, obj, - MjModel, MjrContext, MjvScene, mjrRect, mjvFigure, + mjModel, mjrContext, mjvScene, mjrRect, mjvFigure, mjtFramebuffer, }; /// Set default mjrContext. /// -/// **note**: [`MjrContext`] calls this function in its `Default` implementation. +/// **note**: [`mjrContext`] calls this function in its `Default` implementation. /* void mjr_defaultContext(mjrContext* con); */ -pub fn mjr_defaultContext() -> MjrContext { +pub fn mjr_defaultContext() -> mjrContext { let mut c = Box::::new_uninit(); unsafe { crate::bindgen::mjr_defaultContext(c.as_mut_ptr()); } - MjrContext::from_raw(Box::into_raw(unsafe { c.assume_init() })) + mjrContext::from_raw(Box::into_raw(unsafe { c.assume_init() })) } /// Allocate resources in custom OpenGL context; fontscale is [`mjtFontScale`]. /// -/// **note**: [`MjrContext`] calls this function in its `new` implementation. +/// **note**: [`mjrContext`] calls this function in its `new` implementation. /* void mjr_makeContext(const mjModel* m, mjrContext* con, int fontscale); */ -pub fn mjr_makeContext(m: &MjModel, con: &mut MjrContext, fontscale: mjtFontScale) { +pub fn mjr_makeContext(m: &mjModel, con: &mut mjrContext, fontscale: mjtFontScale) { unsafe { crate::bindgen::mjr_makeContext(m.as_ptr(), con.as_mut_ptr(), fontscale.0 as i32); } @@ -39,7 +39,7 @@ pub fn mjr_makeContext(m: &MjModel, con: &mut MjrContext, fontscale: mjtFontScal /// Change font of existing context. /* void mjr_changeFont(int fontscale, mjrContext* con); */ -pub fn mjr_changeFont(fontscale: mjtFontScale, con: &mut MjrContext) { +pub fn mjr_changeFont(fontscale: mjtFontScale, con: &mut mjrContext) { unsafe { crate::bindgen::mjr_changeFont(fontscale.0 as i32, con.as_mut_ptr()); } @@ -52,7 +52,7 @@ pub fn mjr_addAux( width: i32, height: i32, samples: i32, - con: &mut MjrContext, + con: &mut mjrContext, ) { unsafe { crate::bindgen::mjr_addAux(index as i32, width, height, samples, con.as_mut_ptr()); @@ -61,16 +61,16 @@ pub fn mjr_addAux( /// Free resources in custom OpenGL context, set to default. /// -/// **note**: [`MjrContext`] calls this function in its `Drop` implementation. +/// **note**: [`mjrContext`] calls this function in its `Drop` implementation. /* void mjr_freeContext(mjrContext* con); */ -pub fn mjr_freeContext(con: &mut MjrContext) { +pub fn mjr_freeContext(con: &mut mjrContext) { unsafe { crate::bindgen::mjr_freeContext(con.as_mut_ptr()); } drop(unsafe { Box::from_raw(con.as_mut_ptr()) }); } /// Resize offscreen buffers. /* void mjr_resizeOffscreen(int width, int height, mjrContext* con); */ -pub fn mjr_resizeOffscreen(width: i32, height: i32, con: &mut MjrContext) { +pub fn mjr_resizeOffscreen(width: i32, height: i32, con: &mut mjrContext) { unsafe { crate::bindgen::mjr_resizeOffscreen(width, height, con.as_mut_ptr()); } @@ -78,7 +78,7 @@ pub fn mjr_resizeOffscreen(width: i32, height: i32, con: &mut MjrContext) { /// Upload texture to GPU, overwriting previous upload if any. /* void mjr_uploadTexture(const mjModel* m, const mjrContext* con, int texid); */ -pub fn mjr_uploadTexture(m: &MjModel, con: &MjrContext, texid: ObjectId) { +pub fn mjr_uploadTexture(m: &mjModel, con: &mjrContext, texid: ObjectId) { unsafe { crate::bindgen::mjr_uploadTexture(m.as_ptr(), con.as_ptr(), texid.index() as i32); } @@ -86,7 +86,7 @@ pub fn mjr_uploadTexture(m: &MjModel, con: &MjrContext, texid: ObjectId) { +pub fn mjr_uploadMesh(m: &mjModel, con: &mjrContext, meshid: ObjectId) { unsafe { crate::bindgen::mjr_uploadMesh(m.as_ptr(), con.as_ptr(), meshid.index() as i32); } @@ -94,7 +94,7 @@ pub fn mjr_uploadMesh(m: &MjModel, con: &MjrContext, meshid: ObjectId /// Upload height field to GPU, overwriting previous upload if any. /* void mjr_uploadHField(const mjModel* m, const mjrContext* con, int hfieldid); */ -pub fn mjr_uploadHField(m: &MjModel, con: &MjrContext, hfieldid: ObjectId) { +pub fn mjr_uploadHField(m: &mjModel, con: &mjrContext, hfieldid: ObjectId) { unsafe { crate::bindgen::mjr_uploadHField(m.as_ptr(), con.as_ptr(), hfieldid.index() as i32); } @@ -102,7 +102,7 @@ pub fn mjr_uploadHField(m: &MjModel, con: &MjrContext, hfieldid: ObjectIdcurrentBuffer current again. /* void mjr_restoreBuffer(const mjrContext* con); */ -pub fn mjr_restoreBuffer(con: &MjrContext) { +pub fn mjr_restoreBuffer(con: &mjrContext) { unsafe { crate::bindgen::mjr_restoreBuffer(con.as_ptr()); } @@ -111,7 +111,7 @@ pub fn mjr_restoreBuffer(con: &MjrContext) { /// Set OpenGL framebuffer for rendering: mjFB_WINDOW or mjFB_OFFSCREEN. /// If only one buffer is available, set that buffer and ignore framebuffer argument. /* void mjr_setBuffer(int framebuffer, mjrContext* con); */ -pub fn mjr_setBuffer(framebuffer: mjtFramebuffer, con: &mut MjrContext) { +pub fn mjr_setBuffer(framebuffer: mjtFramebuffer, con: &mut mjrContext) { unsafe { crate::bindgen::mjr_setBuffer(framebuffer.0 as i32, con.as_mut_ptr()); } @@ -125,7 +125,7 @@ pub fn mjr_readPixels( rgb: &mut [u8], depth: &mut [f32], viewport: mjrRect, - con: &MjrContext, + con: &mjrContext, ) { assert_eq!(rgb.len(), (viewport.width * viewport.height * 3) as usize); assert_eq!(depth.len(), viewport.width as usize * viewport.height as usize); @@ -147,7 +147,7 @@ pub fn mjr_drawPixels( rgb: &[u8], depth: &[f32], viewport: mjrRect, - con: &MjrContext, + con: &mjrContext, ) { assert_eq!(rgb.len(), (viewport.width * viewport.height * 3) as usize); assert_eq!(depth.len(), viewport.width as usize * viewport.height as usize); @@ -170,7 +170,7 @@ pub fn mjr_blitBuffer( dst: mjrRect, flg_color: bool, flg_depth: bool, - con: &MjrContext, + con: &mjrContext, ) { unsafe { crate::bindgen::mjr_blitBuffer( @@ -185,7 +185,7 @@ pub fn mjr_blitBuffer( /// Set Aux buffer for custom OpenGL rendering (call restoreBuffer when done). /* void mjr_setAux(int index, const mjrContext* con); */ -pub fn mjr_setAux(index: i32, con: &MjrContext) { +pub fn mjr_setAux(index: i32, con: &mjrContext) { unsafe { crate::bindgen::mjr_setAux(index, con.as_ptr()); } @@ -198,7 +198,7 @@ pub fn mjr_blitAux( src: mjrRect, left: i32, bottom: i32, - con: &MjrContext, + con: &mjrContext, ) { unsafe { crate::bindgen::mjr_blitAux(index as i32, src, left, bottom, con.as_ptr()); @@ -211,7 +211,7 @@ pub fn mjr_blitAux( pub fn mjr_text( font: mjtFontScale, txt: &str, - con: &MjrContext, + con: &mjrContext, x: f32, y: f32, Rgb { r, g, b }: Rgb, @@ -240,7 +240,7 @@ pub fn mjr_overlay( viewport: mjrRect, overlay: &str, overlay2: &str, - con: &MjrContext, + con: &mjrContext, ) { let c_overlay = std::ffi::CString::new(overlay).expect("`overlay` has invalid UTF-8"); let c_overlay2 = std::ffi::CString::new(overlay2).expect("`overlay2` has invalid UTF-8"); @@ -258,7 +258,7 @@ pub fn mjr_overlay( /// Get maximum viewport for active buffer. /* mjrRect mjr_maxViewport(const mjrContext* con); */ -pub fn mjr_maxViewport(con: &MjrContext) -> mjrRect { +pub fn mjr_maxViewport(con: &mjrContext) -> mjrRect { unsafe { crate::bindgen::mjr_maxViewport(con.as_ptr()) } } @@ -280,7 +280,7 @@ pub fn mjr_label( txt: &str, text_color: Rgba, background_color: Rgb, - con: &MjrContext, + con: &mjrContext, ) { let c_txt = std::ffi::CString::new(txt).expect("`txt` has invalid UTF-8"); unsafe { @@ -297,7 +297,7 @@ pub fn mjr_label( /// Draw 2D figure. /* void mjr_figure(mjrRect viewport, mjvFigure* fig, const mjrContext* con); */ -pub fn mjr_figure(viewport: mjrRect, fig: &mut mjvFigure, con: &MjrContext) { +pub fn mjr_figure(viewport: mjrRect, fig: &mut mjvFigure, con: &mjrContext) { unsafe { crate::bindgen::mjr_figure(viewport, fig, con.as_ptr()); } @@ -305,7 +305,7 @@ pub fn mjr_figure(viewport: mjrRect, fig: &mut mjvFigure, con: &MjrContext) { /// Render 3D scene. /* void mjr_render(mjrRect viewport, mjvScene* scn, const mjrContext* con); */ -pub fn mjr_render(viewport: mjrRect, scn: &mut MjvScene, con: &MjrContext) { +pub fn mjr_render(viewport: mjrRect, scn: &mut mjvScene, con: &mjrContext) { unsafe { crate::bindgen::mjr_render(viewport, scn.as_mut_ptr(), con.as_ptr()); } diff --git a/src/functions/parse_and_compile.rs b/src/functions/parse_and_compile.rs index 807cd38..8b3d858 100644 --- a/src/functions/parse_and_compile.rs +++ b/src/functions/parse_and_compile.rs @@ -6,10 +6,10 @@ //! in the user-provided string. The model and all files referenced in it //! can be loaded from disk. -use crate::{MjError, MjSpec, MjModel, MjData}; +use crate::{MjError, mjSpec, mjModel, mjData}; /// Parse XML file in MJCF or URDF format, compile it, return low-level model. -pub fn mj_loadXML(filename: impl Into) -> Result { +pub fn mj_loadXML(filename: impl Into) -> Result { let filename = std::ffi::CString::new(filename.into()).map_err(MjError::from_error)?; let mut error = MjError::init(); @@ -26,12 +26,12 @@ pub fn mj_loadXML(filename: impl Into) -> Result { if c_ptr.is_null() { Err(error) } else { - Ok(MjModel::from_raw(c_ptr)) + Ok(mjModel::from_raw(c_ptr)) } } /// Parse spec from XML file. -pub fn mj_parseXML(filename: impl Into) -> Result { +pub fn mj_parseXML(filename: impl Into) -> Result { let filename = std::ffi::CString::new(filename.into()).map_err(MjError::from_error)?; let mut error = MjError::init(); @@ -48,12 +48,12 @@ pub fn mj_parseXML(filename: impl Into) -> Result { if c_ptr.is_null() { Err(error) } else { - Ok(MjSpec::from_raw(c_ptr)) + Ok(mjSpec::from_raw(c_ptr)) } } /// Parse spec from XML string. -pub fn mj_parseXMLString(xml: impl Into) -> Result { +pub fn mj_parseXMLString(xml: impl Into) -> Result { let xml = std::ffi::CString::new(xml.into()).map_err(MjError::from_error)?; let mut error = MjError::init(); @@ -70,20 +70,20 @@ pub fn mj_parseXMLString(xml: impl Into) -> Result { if c_ptr.is_null() { Err(error) } else { - Ok(MjSpec::from_raw(c_ptr)) + Ok(mjSpec::from_raw(c_ptr)) } } /// Compile mjSpec to mjModel. A spec can be edited and compiled multiple times, /// returning a new mjModel instance that takes the edits into account. /// If compilation fails, `mj_compile` returns NULL; the error can be read with `mjs_getError`. -pub fn mj_compile(s: &mut MjSpec) -> Option { +pub fn mj_compile(s: &mut mjSpec) -> Option { let c_ptr = unsafe { crate::bindgen::mj_compile(s.as_mut_ptr(), std::ptr::null()) }; if c_ptr.is_null() { None } else { - Some(MjModel::from_raw(c_ptr)) + Some(mjModel::from_raw(c_ptr)) } } @@ -99,7 +99,7 @@ pub fn mj_compile(s: &mut MjSpec) -> Option { /// `mj_recompile` returns 0 if compilation succeed. In the case of failure, /// the given mjModel and mjData instances will be deleted; as in `mj_compile`, /// the compilation error can be read with `mjs_getError`. -pub fn mj_recompile(s: &mut MjSpec, m: &mut MjModel, d: &mut MjData) -> Result<(), ()> { +pub fn mj_recompile(s: &mut mjSpec, m: &mut mjModel, d: &mut mjData) -> Result<(), ()> { let status = unsafe { crate::bindgen::mj_recompile( s.as_mut_ptr(), @@ -123,7 +123,7 @@ pub fn mj_recompile(s: &mut MjSpec, m: &mut MjModel, d: &mut MjData) -> Result<( /// old and new model loading and saving mechanisms. pub fn mj_saveLastXML( filename: impl Into, - m: &MjModel, + m: &mjModel, ) -> Result<(), MjError> { let filename = std::ffi::CString::new(filename.into()).map_err(MjError::from_error)?; @@ -152,9 +152,9 @@ pub fn mj_freeLastXML() { /// Save spec to XML string. /// XML saving automatically compiles the spec before saving. -pub fn mj_saveXMLString(s: &MjSpec) -> Result { +pub fn mj_saveXMLString(s: &mjSpec) -> Result { fn proc_inner( - s: &MjSpec, + s: &mjSpec, output_buffer: &mut Vec, ) -> (i32, MjError) { let mut error = MjError::init(); @@ -174,7 +174,7 @@ pub fn mj_saveXMLString(s: &MjSpec) -> Result { #[cold] #[inline(never)] fn retry( - s: &MjSpec, + s: &mjSpec, output_buffer: &mut Vec, ) -> (i32, MjError) { proc_inner(s, output_buffer) @@ -202,7 +202,7 @@ pub fn mj_saveXMLString(s: &MjSpec) -> Result { /// Save spec to XML file. XML saving requires that the spec first be compiled. pub fn mj_saveXML( - s: &MjSpec, + s: &mjSpec, filename: impl Into, ) -> Result<(), MjError> { let filename = std::ffi::CString::new(filename.into()).map_err(MjError::from_error)?; diff --git a/src/functions/ray_casting.rs b/src/functions/ray_casting.rs index 7c2a994..dabc777 100644 --- a/src/functions/ray_casting.rs +++ b/src/functions/ray_casting.rs @@ -27,8 +27,8 @@ use crate::{obj, ObjectId, VertexId}; const mjtByte* geomgroup, mjtByte flg_static, int bodyexclude, int* geomid, mjtNum* dist, int nray, mjtNum cutoff); */ pub fn mj_multiRay( - m: &crate::MjModel, - d: &mut crate::MjData, + m: &crate::mjModel, + d: &mut crate::mjData, pnt: [f64; 3], vec: [[f64; 3]; N_RAY], geomgroup: Option<&[u8]>, @@ -80,8 +80,8 @@ pub fn mj_multiRay( const mjtByte* geomgroup, mjtByte flg_static, int bodyexclude, int geomid[1]); */ pub fn mj_ray( - m: &crate::MjModel, - d: &crate::MjData, + m: &crate::mjModel, + d: &crate::mjData, pnt: [f64; 3], vec: [f64; 3], geomgroup: Option<[bool; crate::bindgen::mjNGROUP as usize]>, @@ -116,8 +116,8 @@ pub fn mj_ray( /* mjtNum mj_rayHfield(const mjModel* m, const mjData* d, int geomid, const mjtNum pnt[3], const mjtNum vec[3]); */ pub fn mj_rayHfield( - m: &crate::MjModel, - d: &crate::MjData, + m: &crate::mjModel, + d: &crate::mjData, geomid: ObjectId, pnt: [f64; 3], vec: [f64; 3], @@ -143,8 +143,8 @@ pub fn mj_rayHfield( /* mjtNum mj_rayMesh(const mjModel* m, const mjData* d, int geomid, const mjtNum pnt[3], const mjtNum vec[3]); */ pub fn mj_rayMesh( - m: &crate::MjModel, - d: &crate::MjData, + m: &crate::mjModel, + d: &crate::mjData, geomid: ObjectId, pnt: [f64; 3], vec: [f64; 3], @@ -201,8 +201,8 @@ pub fn mju_rayGeom( mjtByte flg_edge, mjtByte flg_face, mjtByte flg_skin, int flexid, const mjtNum* pnt, const mjtNum* vec, int vertid[1]); */ pub fn mju_rayFlex( - m: &crate::MjModel, - d: &crate::MjData, + m: &crate::mjModel, + d: &crate::mjData, flex_layer: Option, flg_vert: bool, flg_edge: bool, diff --git a/src/functions/sub_components.rs b/src/functions/sub_components.rs index a85557a..d4935d7 100644 --- a/src/functions/sub_components.rs +++ b/src/functions/sub_components.rs @@ -4,105 +4,105 @@ /// Evaluate position-dependent sensors. /* void mj_sensorPos(const mjModel* m, mjData* d); */ -pub fn mj_sensorPos(m: &crate::MjModel, d: &mut crate::MjData) { +pub fn mj_sensorPos(m: &crate::mjModel, d: &mut crate::mjData) { unsafe { crate::bindgen::mj_sensorPos(m.as_ptr(), d.as_mut_ptr()) } } /// Evaluate velocity-dependent sensors. /* void mj_sensorVel(const mjModel* m, mjData* d); */ -pub fn mj_sensorVel(m: &crate::MjModel, d: &mut crate::MjData) { +pub fn mj_sensorVel(m: &crate::mjModel, d: &mut crate::mjData) { unsafe { crate::bindgen::mj_sensorVel(m.as_ptr(), d.as_mut_ptr()) } } /// Evaluate acceleration and force-dependent sensors. /* void mj_sensorAcc(const mjModel* m, mjData* d); */ -pub fn mj_sensorAcc(m: &crate::MjModel, d: &mut crate::MjData) { +pub fn mj_sensorAcc(m: &crate::mjModel, d: &mut crate::mjData) { unsafe { crate::bindgen::mj_sensorAcc(m.as_ptr(), d.as_mut_ptr()) } } /// Evaluate position-dependent energy (potential). /* void mj_energyPos(const mjModel* m, mjData* d); */ -pub fn mj_energyPos(m: &crate::MjModel, d: &mut crate::MjData) { +pub fn mj_energyPos(m: &crate::mjModel, d: &mut crate::mjData) { unsafe { crate::bindgen::mj_energyPos(m.as_ptr(), d.as_mut_ptr()) } } /// Evaluate velocity-dependent energy (kinetic). /* void mj_energyVel(const mjModel* m, mjData* d); */ -pub fn mj_energyVel(m: &crate::MjModel, d: &mut crate::MjData) { +pub fn mj_energyVel(m: &crate::mjModel, d: &mut crate::mjData) { unsafe { crate::bindgen::mj_energyVel(m.as_ptr(), d.as_mut_ptr()) } } /// Check qpos, reset if any element is too big or nan. /* void mj_checkPos(const mjModel* m, mjData* d); */ -pub fn mj_checkPos(m: &crate::MjModel, d: &mut crate::MjData) { +pub fn mj_checkPos(m: &crate::mjModel, d: &mut crate::mjData) { unsafe { crate::bindgen::mj_checkPos(m.as_ptr(), d.as_mut_ptr()) } } /// Check qvel, reset if any element is too big or nan. /* void mj_checkVel(const mjModel* m, mjData* d); */ -pub fn mj_checkVel(m: &crate::MjModel, d: &mut crate::MjData) { +pub fn mj_checkVel(m: &crate::mjModel, d: &mut crate::mjData) { unsafe { crate::bindgen::mj_checkVel(m.as_ptr(), d.as_mut_ptr()) } } /// Check qacc, reset if any element is too big or nan. /* void mj_checkAcc(const mjModel* m, mjData* d); */ -pub fn mj_checkAcc(m: &crate::MjModel, d: &mut crate::MjData) { +pub fn mj_checkAcc(m: &crate::mjModel, d: &mut crate::mjData) { unsafe { crate::bindgen::mj_checkAcc(m.as_ptr(), d.as_mut_ptr()) } } /// Run forward kinematics. /* void mj_kinematics(const mjModel* m, mjData* d); */ -pub fn mj_kinematics(m: &crate::MjModel, d: &mut crate::MjData) { +pub fn mj_kinematics(m: &crate::mjModel, d: &mut crate::mjData) { unsafe { crate::bindgen::mj_kinematics(m.as_ptr(), d.as_mut_ptr()) } } /// Map inertias and motion dofs to global frame centered at CoM. /* void mj_comPos(const mjModel* m, mjData* d); */ -pub fn mj_comPos(m: &crate::MjModel, d: &mut crate::MjData) { +pub fn mj_comPos(m: &crate::mjModel, d: &mut crate::mjData) { unsafe { crate::bindgen::mj_comPos(m.as_ptr(), d.as_mut_ptr()) } } /// Compute camera and light positions and orientations. /* void mj_camlight(const mjModel* m, mjData* d); */ -pub fn mj_camlight(m: &crate::MjModel, d: &mut crate::MjData) { +pub fn mj_camlight(m: &crate::mjModel, d: &mut crate::mjData) { unsafe { crate::bindgen::mj_camlight(m.as_ptr(), d.as_mut_ptr()) } } /// Compute flex-related quantities. /* void mj_flex(const mjModel* m, mjData* d); */ -pub fn mj_flex(m: &crate::MjModel, d: &mut crate::MjData) { +pub fn mj_flex(m: &crate::mjModel, d: &mut crate::mjData) { unsafe { crate::bindgen::mj_flex(m.as_ptr(), d.as_mut_ptr()) } } /// Compute tendon lengths, velocities and moment arms. /* void mj_tendon(const mjModel* m, mjData* d); */ -pub fn mj_tendon(m: &crate::MjModel, d: &mut crate::MjData) { +pub fn mj_tendon(m: &crate::mjModel, d: &mut crate::mjData) { unsafe { crate::bindgen::mj_tendon(m.as_ptr(), d.as_mut_ptr()) } } /// Compute actuator transmission lengths and moments. /* void mj_transmission(const mjModel* m, mjData* d); */ -pub fn mj_transmission(m: &crate::MjModel, d: &mut crate::MjData) { +pub fn mj_transmission(m: &crate::mjModel, d: &mut crate::mjData) { unsafe { crate::bindgen::mj_transmission(m.as_ptr(), d.as_mut_ptr()) } } /// Run composite rigid body inertia algorithm (CRB). /* void mj_crb(const mjModel* m, mjData* d); */ -pub fn mj_crb(m: &crate::MjModel, d: &mut crate::MjData) { +pub fn mj_crb(m: &crate::mjModel, d: &mut crate::mjData) { unsafe { crate::bindgen::mj_crb(m.as_ptr(), d.as_mut_ptr()) } } /// Compute sparse _L^T D L_ factorizaton of inertia matrix. /* void mj_factorM(const mjModel* m, mjData* d); */ -pub fn mj_factorM(m: &crate::MjModel, d: &mut crate::MjData) { +pub fn mj_factorM(m: &crate::mjModel, d: &mut crate::mjData) { unsafe { crate::bindgen::mj_factorM(m.as_ptr(), d.as_mut_ptr()) } } /// Solve linear system _M x = y_ using factorization: _x = (L^TDL)^{-1} y_ /* void mj_solveM(const mjModel* m, mjData* d, mjtNum* x, const mjtNum* y, int n); */ pub fn mj_solveM( - m: &crate::MjModel, - d: &mut crate::MjData, + m: &crate::mjModel, + d: &mut crate::mjData, x: &mut [f64], y: &[f64], n: usize, @@ -124,8 +124,8 @@ pub fn mj_solveM( /* void mj_solveM2(const mjModel* m, mjData* d, mjtNum* x, const mjtNum* y, const mjtNum* sqrtInvD, int n); */ pub fn mj_solveM2( - m: &crate::MjModel, - d: &mut crate::MjData, + m: &crate::mjModel, + d: &mut crate::mjData, x: &mut [f64], y: &[f64], sqrt_inv_d: &[f64], @@ -148,13 +148,13 @@ pub fn mj_solveM2( /// Compute cvel, cdof_dot. /* void mj_comVel(const mjModel* m, mjData* d); */ -pub fn mj_comVel(m: &crate::MjModel, d: &mut crate::MjData) { +pub fn mj_comVel(m: &crate::mjModel, d: &mut crate::mjData) { unsafe { crate::bindgen::mj_comVel(m.as_ptr(), d.as_mut_ptr()) } } /// Compute qfrc_passive from spring-dampers, gravity compensation and fluid forces. /* void mj_passive(const mjModel* m, mjData* d); */ -pub fn mj_passive(m: &crate::MjModel, d: &mut crate::MjData) { +pub fn mj_passive(m: &crate::mjModel, d: &mut crate::mjData) { unsafe { crate::bindgen::mj_passive(m.as_ptr(), d.as_mut_ptr()) } } @@ -168,7 +168,7 @@ pub fn mj_passive(m: &crate::MjModel, d: &mut crate::MjData) { /// of [stage](https://mujoco.readthedocs.io/en/stable/XMLreference.html#sensor-user-needstage) /// “vel”. /* void mj_subtreeVel(const mjModel* m, mjData* d); */ -pub fn mj_subtreeVel(m: &crate::MjModel, d: &mut crate::MjData) { +pub fn mj_subtreeVel(m: &crate::mjModel, d: &mut crate::mjData) { unsafe { crate::bindgen::mj_subtreeVel(m.as_ptr(), d.as_mut_ptr()) } } @@ -176,8 +176,8 @@ pub fn mj_subtreeVel(m: &crate::MjModel, d: &mut crate::MjData) { /// `flg_acc = false` removes the inertial term (i.e. assumes _\ddot{q} = 0_). /* void mj_rne(const mjModel* m, mjData* d, int flg_acc, mjtNum* result); */ pub fn mj_rne( - m: &crate::MjModel, - d: &mut crate::MjData, + m: &crate::mjModel, + d: &mut crate::mjData, flg_acc: bool, ) -> Vec { let mut result = vec![0.0; m.nv()]; @@ -213,37 +213,37 @@ pub fn mj_rne( /// of [stage](https://mujoco.readthedocs.io/en/stable/XMLreference.html#sensor-user-needstage) /// “acc”. /* void mj_rnePostConstraint(const mjModel* m, mjData* d); */ -pub fn mj_rnePostConstraint(m: &crate::MjModel, d: &mut crate::MjData) { +pub fn mj_rnePostConstraint(m: &crate::mjModel, d: &mut crate::mjData) { unsafe { crate::bindgen::mj_rnePostConstraint(m.as_ptr(), d.as_mut_ptr()) } } /// Run collision detection. /* void mj_collision(const mjModel* m, mjData* d); */ -pub fn mj_collision(m: &crate::MjModel, d: &mut crate::MjData) { +pub fn mj_collision(m: &crate::mjModel, d: &mut crate::mjData) { unsafe { crate::bindgen::mj_collision(m.as_ptr(), d.as_mut_ptr()) } } /// Construct constraints. /* void mj_makeConstraint(const mjModel* m, mjData* d); */ -pub fn mj_makeConstraint(m: &crate::MjModel, d: &mut crate::MjData) { +pub fn mj_makeConstraint(m: &crate::mjModel, d: &mut crate::mjData) { unsafe { crate::bindgen::mj_makeConstraint(m.as_ptr(), d.as_mut_ptr()) } } /// Find constraint islands. /* void mj_island(const mjModel* m, mjData* d); */ -pub fn mj_island(m: &crate::MjModel, d: &mut crate::MjData) { +pub fn mj_island(m: &crate::mjModel, d: &mut crate::mjData) { unsafe { crate::bindgen::mj_island(m.as_ptr(), d.as_mut_ptr()) } } /// Compute inverse constraint inertia efc_AR. /* void mj_projectConstraint(const mjModel* m, mjData* d); */ -pub fn mj_projectConstraint(m: &crate::MjModel, d: &mut crate::MjData) { +pub fn mj_projectConstraint(m: &crate::mjModel, d: &mut crate::mjData) { unsafe { crate::bindgen::mj_projectConstraint(m.as_ptr(), d.as_mut_ptr()) } } /// Compute efc_vel, efc_aref. /* void mj_referenceConstraint(const mjModel* m, mjData* d); */ -pub fn mj_referenceConstraint(m: &crate::MjModel, d: &mut crate::MjData) { +pub fn mj_referenceConstraint(m: &crate::mjModel, d: &mut crate::mjData) { unsafe { crate::bindgen::mj_referenceConstraint(m.as_ptr(), d.as_mut_ptr()) } } @@ -253,8 +253,8 @@ pub fn mj_referenceConstraint(m: &crate::MjModel, d: &mut crate::MjData) { /* void mj_constraintUpdate(const mjModel* m, mjData* d, const mjtNum* jar, mjtNum cost[1], int flg_coneHessian); */ pub fn mj_constraintUpdate( - m: &crate::MjModel, - d: &mut crate::MjData, + m: &crate::mjModel, + d: &mut crate::mjData, jar: &[f64], flg_cone_hessian: bool, ) -> f64 { diff --git a/src/functions/support.rs b/src/functions/support.rs index 0199a15..645a1ed 100644 --- a/src/functions/support.rs +++ b/src/functions/support.rs @@ -5,17 +5,17 @@ //! Support functions are called within the simulator but //! some of them can also be useful for custom computations. -use crate::{obj, mjContact, MjData, MjModel, ObjectId}; +use crate::{obj, mjContact, mjData, mjModel, ObjectId}; /// Returns the number of mjtNum⁠s required for a given state specification. The bits of the integer spec correspond to element fields of mjtState. -pub fn mj_stateSize(m: &MjModel, spec: crate::bindgen::mjtState) -> usize { +pub fn mj_stateSize(m: &mjModel, spec: crate::bindgen::mjtState) -> usize { unsafe { crate::bindgen::mj_stateSize(m.as_ptr(), spec.0 as u32) as _ } } /// Copy concatenated state components specified by spec from d into state. The bits of the integer spec correspond to element fields of mjtState. Fails with mju_error if spec is invalid. pub fn mj_getState( - m: &MjModel, - d: &MjData, + m: &mjModel, + d: &mjData, state: &mut [f64], spec: crate::bindgen::mjtState, ) { @@ -34,8 +34,8 @@ pub fn mj_getState( /// Copy concatenated state components specified by spec from state into d. The bits of the integer spec correspond to element fields of mjtState. Fails with mju_error if spec is invalid. pub fn mj_setState( - m: &MjModel, - d: &mut MjData, + m: &mjModel, + d: &mut mjData, state: &[f64], spec: crate::bindgen::mjtState, ) { @@ -53,12 +53,12 @@ pub fn mj_setState( } /// Copy current state to the k-th model keyframe. -pub fn mj_setKeyframe(m: &mut MjModel, d: &MjData, k: usize) { +pub fn mj_setKeyframe(m: &mut mjModel, d: &mjData, k: usize) { unsafe { crate::bindgen::mj_setKeyframe(m.as_mut_ptr(), d.as_ptr(), k as i32) } } /// Add contact to d->contact list -pub fn mj_addContact(m: &MjModel, d: &mut MjData, con: &mjContact) -> Result<(), ()> { +pub fn mj_addContact(m: &mjModel, d: &mut mjData, con: &mjContact) -> Result<(), ()> { let res = unsafe { crate::bindgen::mj_addContact(m.as_ptr(), d.as_mut_ptr(), con) }; /* https://mujoco.readthedocs.io/en/stable/APIreference/APIfunctions.html#mj-addcontact @@ -68,22 +68,22 @@ pub fn mj_addContact(m: &MjModel, d: &mut MjData, con: &mjContact) -> Result<(), } /// Determine type of friction cone. -pub fn mj_isPyramidal(m: &MjModel) -> bool { +pub fn mj_isPyramidal(m: &mjModel) -> bool { unsafe { crate::bindgen::mj_isPyramidal(m.as_ptr()) != 0 } } /// Determine type of constraint Jacobian. -pub fn mj_isSparse(m: &MjModel) -> bool { +pub fn mj_isSparse(m: &mjModel) -> bool { unsafe { crate::bindgen::mj_isSparse(m.as_ptr()) != 0 } } /// Determine type of solver (PGS is dual, CG and Newton are primal). -pub fn mj_isDual(m: &MjModel) -> bool { +pub fn mj_isDual(m: &mjModel) -> bool { unsafe { crate::bindgen::mj_isDual(m.as_ptr()) != 0 } } /// This function multiplies the constraint Jacobian mjData.efc_J by a vector. Note that the Jacobian can be either dense or sparse; the function is aware of this setting. Multiplication by J maps velocities from joint space to constraint space. -pub fn mj_mulJacVec(m: &MjModel, d: &MjData, mut vec: Vec) -> Vec { +pub fn mj_mulJacVec(m: &mjModel, d: &mjData, mut vec: Vec) -> Vec { #[cfg(debug_assertions)] { assert_eq!(vec.len(), m.nv()); } @@ -100,7 +100,7 @@ pub fn mj_mulJacVec(m: &MjModel, d: &MjData, mut vec: Vec) -> Vec { } /// Same as mj_mulJacVec but multiplies by the transpose of the Jacobian. This maps forces from constraint space to joint space. -pub fn mj_mulJacTVec(m: &MjModel, d: &MjData, mut vec: Vec) -> Vec { +pub fn mj_mulJacTVec(m: &mjModel, d: &mjData, mut vec: Vec) -> Vec { #[cfg(debug_assertions)] { assert_eq!(vec.len(), d.nefc()); } @@ -139,8 +139,8 @@ pub fn mj_mulJacTVec(m: &MjModel, d: &MjData, mut vec: Vec) -> Vec { /// The minimal pipeline stages required for Jacobian computations to be consistent /// with the current generalized positions mjData.qpos are mj_kinematics followed by mj_comPos. pub fn mj_jac( - m: &MjModel, - d: &MjData, + m: &mjModel, + d: &mjData, body: ObjectId, point: [f64; 3], ) -> (Vec, Vec) { @@ -161,8 +161,8 @@ pub fn mj_jac( /// This and the remaining variants of the Jacobian function call mj_jac internally, with the center of the body, geom or site. They are just shortcuts; the same can be achieved by calling mj_jac directly. pub fn mj_jacBody( - m: &MjModel, - d: &MjData, + m: &mjModel, + d: &mjData, body: ObjectId, ) -> (Vec, Vec) { let mut jacp = vec![0.0; 3 * m.nv() as usize]; @@ -181,8 +181,8 @@ pub fn mj_jacBody( /// Compute body center-of-mass end-effector Jacobian. pub fn mj_jacBodyCom( - m: &MjModel, - d: &MjData, + m: &mjModel, + d: &mjData, body: ObjectId, ) -> (Vec, Vec) { let mut jacp = vec![0.0; 3 * m.nv() as usize]; @@ -201,8 +201,8 @@ pub fn mj_jacBodyCom( // Compute geom end-effector Jacobian. pub fn mj_jacGeom( - m: &MjModel, - d: &MjData, + m: &mjModel, + d: &mjData, geom: ObjectId, ) -> (Vec, Vec) { let mut jacp = vec![0.0; 3 * m.nv() as usize]; @@ -221,8 +221,8 @@ pub fn mj_jacGeom( /// Compute site end-effector Jacobian. pub fn mj_jacSite( - m: &MjModel, - d: &MjData, + m: &mjModel, + d: &mjData, site: ObjectId, ) -> (Vec, Vec) { let mut jacp = vec![0.0; 3 * m.nv() as usize]; @@ -241,8 +241,8 @@ pub fn mj_jacSite( /// Compute translation end-effector Jacobian of point, and rotation Jacobian of axis. pub fn mj_jacPointAxis( - m: &MjModel, - d: &mut MjData, + m: &mjModel, + d: &mut mjData, body: ObjectId, point: [f64; 3], axis: [f64; 3], @@ -266,8 +266,8 @@ pub fn mj_jacPointAxis( /// This function computes the time-derivative of an end-effector kinematic Jacobian computed by mj_jac. The minimal pipeline stages required for computation to be consistent with the current generalized positions and velocities mjData.{qpos, qvel} are mj_kinematics, mj_comPos, pub fn mj_jacDot( - m: &MjModel, - d: &MjData, + m: &mjModel, + d: &mjData, body: ObjectId, point: [f64; 3], ) -> (Vec, Vec) { @@ -291,8 +291,8 @@ pub fn mj_jacDot( /// More precisely if *h* is the subtree angular momentum of body id in mjData.subtree_angmom (reported by the subtreeangmom sensor) /// and *qdot* ​is the generalized velocity mjData.qvel, then *h = H qdot* pub fn mj_angmomMat( - m: &MjModel, - d: &mut MjData, + m: &mjModel, + d: &mut mjData, body: ObjectId, ) -> Vec { let mut res = vec![0.0; 3 * m.nv()]; @@ -320,13 +320,13 @@ pub fn mj_angmomMat( /// "path/to/model.xml" /// ).unwrap(); /// # } -/// # fn example(model: &rusty_mujoco::MjModel) { +/// # fn example(model: &rusty_mujoco::mjModel) { /// let body_id = mj_name2id::(&model, "body_name"); /// println!("Body ID: {:?}", body_id); /// # } /// ``` pub fn mj_name2id( - m: &MjModel, + m: &mjModel, name: &str, ) -> Option> { let c_name = std::ffi::CString::new(name).expect("`name` contains null bytes"); @@ -338,7 +338,7 @@ pub fn mj_name2id( /// Get name of object with the specified mjtObj type and id, returns `None` if name not found. pub fn mj_id2name( - m: &MjModel, + m: &mjModel, id: ObjectId, ) -> String { let c_name = unsafe { @@ -354,7 +354,7 @@ pub fn mj_id2name( /// `M` must be of the same size as mjData.`qM`. /// Returned one is of size `nv x nv`, pub fn mj_fullM( - m: &MjModel, + m: &mjModel, M: &[f64], ) -> Vec { #[cfg(debug_assertions)] { @@ -378,8 +378,8 @@ pub fn mj_fullM( /// and then user regular matrix-vector multiplication, /// but this is slower because it no longer benefits from sparsity. pub fn mj_mulM( - m: &MjModel, - d: &MjData, + m: &mjModel, + d: &mjData, mut vec: Vec, ) -> Vec { #[cfg(debug_assertions)] { @@ -399,8 +399,8 @@ pub fn mj_mulM( /// Multiply vector by (inertia matrix)^(1/2). pub fn mj_mulM2( - m: &MjModel, - d: &MjData, + m: &mjModel, + d: &mjData, mut vec: Vec, ) -> Vec { #[cfg(debug_assertions)] { @@ -422,8 +422,8 @@ pub fn mj_mulM2( /// Destination can be sparse or dense when all int are `None`. /* void mj_addM(const mjModel* m, mjData* d, mjtNum* dst, int* rownnz, int* rowadr, int* colind); */ pub fn mj_addM( - m: &MjModel, - d: &mut MjData, + m: &mjModel, + d: &mut mjData, dst: &mut [f64], rownnz: Option<&mut [i32]>, rowadr: Option<&mut [i32]>, @@ -462,8 +462,8 @@ pub fn mj_addM( const mjtNum force[3], const mjtNum torque[3], const mjtNum point[3], int body, mjtNum* qfrc_target); */ pub fn mj_applyFT( - m: &MjModel, - d: &mut MjData, + m: &mjModel, + d: &mut mjData, body: ObjectId, point: [f64; 3], force: [f64; 3], @@ -487,8 +487,8 @@ pub fn mj_applyFT( /* void mj_objectVelocity(const mjModel* m, const mjData* d, int objtype, int objid, mjtNum res[6], int flg_local); */ pub fn mj_objectVelocity( - m: &MjModel, - d: &MjData, + m: &mjModel, + d: &mjData, object: ObjectId, local: bool, ) -> [f64; 6] { @@ -514,8 +514,8 @@ pub fn mj_objectVelocity( /* void mj_objectAcceleration(const mjModel* m, const mjData* d, int objtype, int objid, mjtNum res[6], int flg_local); */ pub fn mj_objectAcceleration( - m: &MjModel, - d: &MjData, + m: &mjModel, + d: &mjData, object: ObjectId, local: bool, ) -> [f64; 6] { @@ -540,8 +540,8 @@ pub fn mj_objectAcceleration( /* mjtNum mj_geomDistance(const mjModel* m, const mjData* d, int geom1, int geom2, mjtNum distmax, mjtNum fromto[6]); */ pub fn mj_geomDistance( - m: &MjModel, - d: &MjData, + m: &mjModel, + d: &mjData, geom1: ObjectId, geom2: ObjectId, distmax: f64, @@ -563,8 +563,8 @@ pub fn mj_geomDistance( /// Extract 6D force:torque given contact id, in the contact frame. /* void mj_contactForce(const mjModel* m, const mjData* d, int id, mjtNum result[6]); */ pub fn mj_contactForce( - m: &MjModel, - d: &MjData, + m: &mjModel, + d: &mjData, contact_id: usize, ) -> [f64; 6] { let mut result = [0.0; 6]; @@ -593,7 +593,7 @@ void mj_differentiatePos(const mjModel* m, mjtNum* qvel, mjtNum dt, const mjtNum* qpos1, const mjtNum* qpos2); */ pub fn mj_differentiatePos( - m: &MjModel, + m: &mjModel, qpos1: &[f64], qpos2: &[f64], dt: f64, @@ -618,7 +618,7 @@ pub fn mj_differentiatePos( /// This is the opposite of mj_differentiatePos. It adds a vector in the format of qvel (scaled by dt) to a vector in the format of qpos. /* void mj_integratePos(const mjModel* m, mjtNum* qpos, const mjtNum* qvel, mjtNum dt); */ pub fn mj_integratePos( - m: &MjModel, + m: &mjModel, qpos: &mut [f64], qvel: &[f64], dt: f64, @@ -640,7 +640,7 @@ pub fn mj_integratePos( /// Normalize all quaternions in qpos-type vector. /* void mj_normalizeQuat(const mjModel* m, mjtNum* qpos); */ pub fn mj_normalizeQuat( - m: &MjModel, + m: &mjModel, qpos: &mut [f64], ) { #[cfg(debug_assertions)] { @@ -655,7 +655,7 @@ pub fn mj_normalizeQuat( /* void mj_local2Global(mjData* d, mjtNum xpos[3], mjtNum xmat[9], const mjtNum pos[3], const mjtNum quat[4], int body, mjtByte sameframe); */ pub fn mj_local2Global( - d: &mut MjData, + d: &mut mjData, xpos: &mut [f64; 3], xmat: &mut [f64; 9], pos: &[f64; 3], @@ -677,14 +677,14 @@ pub fn mj_local2Global( } /// Sum all body masses. -pub fn mj_getTotalmass(m: &MjModel) -> f64 { +pub fn mj_getTotalmass(m: &mjModel) -> f64 { unsafe { crate::bindgen::mj_getTotalmass(m.as_ptr()) } } /// Scale body masses and inertias to achieve specified total mass. /* void mj_setTotalmass(mjModel* m, mjtNum newmass); */ pub fn mj_setTotalmass( - m: &mut MjModel, + m: &mut mjModel, newmass: f64, ) { unsafe { crate::bindgen::mj_setTotalmass(m.as_mut_ptr(), newmass) } @@ -694,7 +694,7 @@ pub fn mj_setTotalmass( /// `None`: invalid plugin instance ID or attribute name /* const char* mj_getPluginConfig(const mjModel* m, int plugin_id, const char* attrib); */ pub fn mj_getPluginConfig( - m: &MjModel, + m: &mjModel, plugin_id: ObjectId, attrib: &str, ) -> Option { diff --git a/src/functions/ui_framework.rs b/src/functions/ui_framework.rs index bbee87a..0d37eb8 100644 --- a/src/functions/ui_framework.rs +++ b/src/functions/ui_framework.rs @@ -2,7 +2,7 @@ //! //! For a high-level description of the UI framework, see [User Interface](https://mujoco.readthedocs.io/en/stable/programming/ui.html#ui). -use crate::{MjrContext, mjUI, mjuiDef, mjuiItem, mjuiThemeColor, mjuiThemeSpacing}; +use crate::{mjrContext, mjUI, mjuiDef, mjuiItem, mjuiThemeColor, mjuiThemeSpacing}; /// Get builtin UI theme spacing (ind: 0-1). /* mjuiThemeSpacing mjui_themeSpacing(int ind); */ @@ -74,7 +74,7 @@ pub fn mjui_addToSection( /// Compute UI sizes. /* void mjui_resize(mjUI* ui, const mjrContext* con); */ -pub fn mjui_resize(ui: &mut mjUI, con: &MjrContext) { +pub fn mjui_resize(ui: &mut mjUI, con: &mjrContext) { unsafe { crate::bindgen::mjui_resize(ui, con.as_ptr()) } } @@ -94,7 +94,7 @@ pub fn mjui_update( item: Option, ui: &mjUI, state: &crate::mjuiState, - con: &MjrContext, + con: &mjrContext, ) { unsafe { crate::bindgen::mjui_update( @@ -119,7 +119,7 @@ pub fn mjui_update( pub fn mjui_event<'ui>( ui: &'ui mut mjUI, state: &mut crate::mjuiState, - con: &MjrContext, + con: &mjrContext, ) -> Option<&'ui mut mjuiItem> { let item = unsafe { crate::bindgen::mjui_event(ui, state, con.as_ptr()) }; if item.is_null() {None} else {Some(unsafe { &mut *item })} @@ -133,6 +133,6 @@ pub fn mjui_event<'ui>( /// while `mjui_update` is called only when changes in the UI take place. /// dsffsdg /* void mjui_render(mjUI* ui, const mjuiState* state, const mjrContext* con); */ -pub fn mjui_render(ui: &mut mjUI, state: &crate::mjuiState, con: &MjrContext) { +pub fn mjui_render(ui: &mut mjUI, state: &crate::mjuiState, con: &mjrContext) { unsafe { crate::bindgen::mjui_render(ui, state, con.as_ptr()) } } diff --git a/src/functions/visualization.rs b/src/functions/visualization.rs index 0759924..2cd0b98 100644 --- a/src/functions/visualization.rs +++ b/src/functions/visualization.rs @@ -8,7 +8,7 @@ //! for illustration of how to use these functions. use crate::{ - MjModel, MjData, MjvScene, mjvOption, mjvCamera, mjvPerturb, mjvGeom, mjvFigure, + mjModel, mjData, mjvScene, mjvOption, mjvCamera, mjvPerturb, mjvGeom, mjvFigure, mjtGeom, }; @@ -83,16 +83,16 @@ pub fn mjv_connector( /// Set default abstract scene. /// -/// **note**: [`MjvScene`] calls this function in its `Default` implementation. +/// **note**: [`mjvScene`] calls this function in its `Default` implementation. /// /// **note**: Call [`mjv_makeScene`] to allocate resources in abstract scene /// before starting a simulation with the `mjvScene`. /// /* void mjv_defaultScene(mjvScene* scn); */ -pub fn mjv_defaultScene() -> MjvScene { +pub fn mjv_defaultScene() -> mjvScene { let mut c = Box::::new_uninit(); unsafe { crate::bindgen::mjv_defaultScene(c.as_mut_ptr()); } - MjvScene::from_raw(Box::into_raw(unsafe { c.assume_init() })) + mjvScene::from_raw(Box::into_raw(unsafe { c.assume_init() })) } /// Allocate resources in abstract scene. @@ -100,8 +100,8 @@ pub fn mjv_defaultScene() -> MjvScene { /// **note**: [`mjvScene`] calls this function in its `new` implementation. /* void mjv_makeScene(const mjModel* m, mjvScene* scn, int maxgeom); */ pub fn mjv_makeScene( - model: &MjModel, - scene: &mut MjvScene, + model: &mjModel, + scene: &mut mjvScene, maxgeom: usize, ) { unsafe { @@ -115,9 +115,9 @@ pub fn mjv_makeScene( /// Free abstract scene. /// -/// **note**: [`MjvScene`] calls this function in its `Drop` implementation. +/// **note**: [`mjvScene`] calls this function in its `Drop` implementation. /* void mjv_freeScene(mjvScene* scn); */ -pub fn mjv_freeScene(scene: &mut MjvScene) { +pub fn mjv_freeScene(scene: &mut mjvScene) { unsafe { crate::bindgen::mjv_freeScene(scene.as_mut_ptr()); } drop(unsafe { Box::from_raw(scene.as_mut_ptr()) }); } @@ -126,13 +126,13 @@ pub fn mjv_freeScene(scene: &mut MjvScene) { /* void mjv_updateScene(const mjModel* m, mjData* d, const mjvOption* opt, const mjvPerturb* pert, mjvCamera* cam, int catmask, mjvScene* scn); */ pub fn mjv_updateScene( - model: &MjModel, - data: &mut MjData, + model: &mjModel, + data: &mut mjData, opt: &mjvOption, pert: Option<&mjvPerturb>, cam: &mut mjvCamera, catmask: crate::bindgen::mjtCatBit, - scene: &mut MjvScene, + scene: &mut mjvScene, ) { unsafe { crate::bindgen::mjv_updateScene( @@ -149,7 +149,7 @@ pub fn mjv_updateScene( /// Copy mjModel, skip large arrays not required for abstract visualization. /* void mjv_copyModel(mjModel* dest, const mjModel* src); */ -pub fn mjv_copyModel(dest: &mut MjModel, src: &MjModel) { +pub fn mjv_copyModel(dest: &mut mjModel, src: &mjModel) { unsafe { crate::bindgen::mjv_copyModel(dest.as_mut_ptr(), src.as_ptr()) } } @@ -157,12 +157,12 @@ pub fn mjv_copyModel(dest: &mut MjModel, src: &MjModel) { /* void mjv_addGeoms(const mjModel* m, mjData* d, const mjvOption* opt, const mjvPerturb* pert, int catmask, mjvScene* scn); */ pub fn mjv_addGeoms( - model: &MjModel, - data: &mut MjData, + model: &mjModel, + data: &mut mjData, opt: &mjvOption, pert: &mjvPerturb, catmask: crate::bindgen::mjtCatBit, - scene: &mut MjvScene, + scene: &mut mjvScene, ) { unsafe { crate::bindgen::mjv_addGeoms( @@ -179,9 +179,9 @@ pub fn mjv_addGeoms( /// Make list of lights. /* void mjv_makeLights(const mjModel* m, const mjData* d, mjvScene* scn); */ pub fn mjv_makeLights( - model: &MjModel, - data: &MjData, - scene: &mut MjvScene, + model: &mjModel, + data: &mjData, + scene: &mut mjvScene, ) { unsafe { crate::bindgen::mjv_makeLights( @@ -195,10 +195,10 @@ pub fn mjv_makeLights( /// Update camera. /* void mjv_updateCamera(const mjModel* m, const mjData* d, mjvCamera* cam, mjvScene* scn); */ pub fn mjv_updateCamera( - model: &MjModel, - data: &MjData, + model: &mjModel, + data: &mjData, cam: &mut mjvCamera, - scene: &mut MjvScene, + scene: &mut mjvScene, ) { unsafe { crate::bindgen::mjv_updateCamera( @@ -213,9 +213,9 @@ pub fn mjv_updateCamera( /// Update skins. /* void mjv_updateSkin(const mjModel* m, const mjData* d, mjvScene* scn); */ pub fn mjv_updateSkin( - model: &MjModel, - data: &MjData, - scene: &mut MjvScene, + model: &mjModel, + data: &mjData, + scene: &mut mjvScene, ) { unsafe { crate::bindgen::mjv_updateSkin( diff --git a/src/id.rs b/src/id.rs index fd3a946..9bae3a9 100644 --- a/src/id.rs +++ b/src/id.rs @@ -216,7 +216,7 @@ mod private { pub trait Obj: Sized + private::Sealed { const TYPE: mjtObj; - fn object_id(model: &crate::MjModel, name: &str) -> Option>; + fn object_id(model: &crate::mjModel, name: &str) -> Option>; } pub struct ObjectId { @@ -269,7 +269,7 @@ macro_rules! obj_types { impl super::private::Sealed for $type_name {} impl super::Obj for $type_name { const TYPE: super::mjtObj = super::mjtObj::$name; - fn object_id(model: &crate::MjModel, name: &str) -> Option> { + fn object_id(model: &crate::mjModel, name: &str) -> Option> { crate::mj_name2id::(model, name) } } @@ -370,7 +370,7 @@ pub mod joint { impl super::private::Sealed for Free {} impl Obj for Free { const TYPE: super::mjtObj = super::mjtObj::JOINT; - fn object_id(model: &crate::MjModel, name: &str) -> Option> { + fn object_id(model: &crate::mjModel, name: &str) -> Option> { let o = obj::Joint::object_id(model, name)?; if model.jnt_type(o) != Self::MJT {return None} Some(unsafe { super::ObjectId::::new_unchecked(o.index) }) @@ -388,7 +388,7 @@ pub mod joint { impl super::private::Sealed for Ball {} impl Obj for Ball { const TYPE: super::mjtObj = super::mjtObj::JOINT; - fn object_id(model: &crate::MjModel, name: &str) -> Option> { + fn object_id(model: &crate::mjModel, name: &str) -> Option> { let o = obj::Joint::object_id(model, name)?; if model.jnt_type(o) != Self::MJT {return None} Some(unsafe { super::ObjectId::::new_unchecked(o.index) }) @@ -406,7 +406,7 @@ pub mod joint { impl super::private::Sealed for Hinge {} impl Obj for Hinge { const TYPE: super::mjtObj = super::mjtObj::JOINT; - fn object_id(model: &crate::MjModel, name: &str) -> Option> { + fn object_id(model: &crate::mjModel, name: &str) -> Option> { let o = obj::Joint::object_id(model, name)?; if model.jnt_type(o) != Self::MJT {return None} Some(unsafe { super::ObjectId::::new_unchecked(o.index) }) @@ -424,7 +424,7 @@ pub mod joint { impl super::private::Sealed for Slide {} impl Obj for Slide { const TYPE: super::mjtObj = super::mjtObj::JOINT; - fn object_id(model: &crate::MjModel, name: &str) -> Option> { + fn object_id(model: &crate::mjModel, name: &str) -> Option> { let o = obj::Joint::object_id(model, name)?; if model.jnt_type(o) != Self::MJT {return None} Some(unsafe { super::ObjectId::::new_unchecked(o.index) }) diff --git a/src/types.rs b/src/types.rs index 19a2f0f..0d97dc9 100644 --- a/src/types.rs +++ b/src/types.rs @@ -5,6 +5,7 @@ macro_rules! resource_wrapper { $T:ident for $Bindgen:path; drop = $drop:path; ) => { + #[allow(non_camel_case_types)] pub struct $T(*mut $Bindgen); impl Drop for $T { fn drop(&mut self) { diff --git a/src/types/mjdata.rs b/src/types/mjdata.rs index 80d1bee..905822f 100644 --- a/src/types/mjdata.rs +++ b/src/types/mjdata.rs @@ -8,10 +8,10 @@ pub use crate::bindgen::{ }; resource_wrapper!( - MjData for crate::bindgen::mjData; + mjData for crate::bindgen::mjData; drop = crate::mj_deleteData; ); -fields_mapping!(MjData { +fields_mapping!(mjData { scalars { // constant sizes narena: usize = "size of the arena in bytes (inclusive of the stack)"; @@ -56,7 +56,7 @@ fields_mapping!(MjData { }); // solver statistics -impl MjData { +impl mjData { /// solver statistics per island, per iteration pub fn solver(&self) -> [crate::mjSolverStat; mjNISLAND as usize * mjNSOLVER as usize] { self.solver @@ -75,9 +75,9 @@ impl MjData { } } -use crate::{MjModel, ObjectId, obj, Joint}; +use crate::{mjModel, ObjectId, obj, Joint}; -impl MjData { +impl mjData { pub fn ctrl(&self, id: ObjectId) -> f64 { unsafe { self.ctrl.add(id.index()).read() } } @@ -85,31 +85,31 @@ impl MjData { unsafe { self.ctrl.add(id.index()).write(value) }; } - pub fn act(&self, id: ObjectId, model: &MjModel) -> Option { + pub fn act(&self, id: ObjectId, model: &mjModel) -> Option { let offset = model.actuator_actadr(id)?; Some(unsafe { self.act.add(offset).read() }) } /// Set the actuator activation value. `None` when the actuator is stateless. - pub fn set_act(&mut self, id: ObjectId, value: f64, model: &MjModel) -> Option<()> { + pub fn set_act(&mut self, id: ObjectId, value: f64, model: &mjModel) -> Option<()> { let offset = model.actuator_actadr(id)?; unsafe { self.act.add(offset).write(value) }; Some(()) } - pub fn qpos(&self, id: ObjectId, model: &MjModel) -> J::Qpos { + pub fn qpos(&self, id: ObjectId, model: &mjModel) -> J::Qpos { let ptr = unsafe { self.qpos.add(model.jnt_qposadr(id)) }; J::Qpos::try_from(unsafe { std::slice::from_raw_parts(ptr, J::QPOS_SIZE) }).ok().unwrap() } - pub fn set_qpos(&mut self, id: ObjectId, qpos: J::Qpos, model: &MjModel) { + pub fn set_qpos(&mut self, id: ObjectId, qpos: J::Qpos, model: &mjModel) { let ptr = unsafe { self.qpos.add(model.jnt_qposadr(id)) }; unsafe { std::ptr::copy_nonoverlapping(qpos.as_ref().as_ptr(), ptr, J::QPOS_SIZE) }; } - pub fn qvel(&self, id: ObjectId, model: &MjModel) -> J::Qvel { + pub fn qvel(&self, id: ObjectId, model: &mjModel) -> J::Qvel { let ptr = unsafe { self.qvel.add(model.jnt_dofadr(id).expect("Currently we don't support `weld` in `joint::`, so this will not be None...")) }; J::Qvel::try_from(unsafe { std::slice::from_raw_parts(ptr, J::QVEL_SIZE) }).ok().unwrap() } - pub fn set_qvel(&mut self, id: ObjectId, qvel: J::Qvel, model: &MjModel) { + pub fn set_qvel(&mut self, id: ObjectId, qvel: J::Qvel, model: &mjModel) { let ptr = unsafe { self.qvel.add(model.jnt_dofadr(id).expect("Currently we don't support `weld` in `joint::`, so this will not be None...")) }; unsafe { std::ptr::copy_nonoverlapping(qvel.as_ref().as_ptr(), ptr, J::QVEL_SIZE) }; } @@ -121,12 +121,12 @@ impl MjData { unsafe { self.qacc_warmstart.add(id.index()).write(value) }; } - pub fn plugin_state(&self, id: ObjectId, model: &MjModel) -> Option { + pub fn plugin_state(&self, id: ObjectId, model: &mjModel) -> Option { let offset = model.plugin_stateadr(id)?; Some(unsafe { self.plugin_state.add(offset).read() }) } /// Set the plugin state value. Returns `None` when the plugin is stateless. - pub fn set_plugin_state(&mut self, id: ObjectId, value: f64, model: &MjModel) -> Option<()> { + pub fn set_plugin_state(&mut self, id: ObjectId, value: f64, model: &mjModel) -> Option<()> { let offset = model.plugin_stateadr(id)?; unsafe { self.plugin_state.add(offset).write(value) }; Some(()) @@ -156,23 +156,23 @@ impl MjData { } /// `None` when the body is not a mocap body. - pub fn mocap_pos(&self, id: ObjectId, model: &MjModel) -> Option<[f64; 3]> { + pub fn mocap_pos(&self, id: ObjectId, model: &mjModel) -> Option<[f64; 3]> { let offset = model.body_mocapid(id)?.index() * 3; Some(std::array::from_fn(|i| unsafe { self.mocap_pos.add(offset + i).read() })) } /// `None` when the body is not a mocap body. - pub fn set_mocap_pos(&mut self, id: ObjectId, pos: [f64; 3], model: &MjModel) -> Option<()> { + pub fn set_mocap_pos(&mut self, id: ObjectId, pos: [f64; 3], model: &mjModel) -> Option<()> { let offset = model.body_mocapid(id)?.index() * 3; unsafe { std::ptr::copy_nonoverlapping(pos.as_ptr(), self.mocap_pos.add(offset), pos.len()) }; Some(()) } - pub fn mocap_quat(&self, id: ObjectId, model: &MjModel) -> Option<[f64; 4]> { + pub fn mocap_quat(&self, id: ObjectId, model: &mjModel) -> Option<[f64; 4]> { let offset = model.body_mocapid(id)?.index() * 4; Some(std::array::from_fn(|i| unsafe { self.mocap_quat.add(offset + i).read() })) } /// `None` when the body is not a mocap body. - pub fn set_mocap_quat(&mut self, id: ObjectId, quat: [f64; 4], model: &MjModel) -> Option<()> { + pub fn set_mocap_quat(&mut self, id: ObjectId, quat: [f64; 4], model: &mjModel) -> Option<()> { let offset = model.body_mocapid(id)?.index() * 4; unsafe { std::ptr::copy_nonoverlapping(quat.as_ptr(), self.mocap_quat.add(offset), quat.len()) }; Some(()) @@ -187,12 +187,12 @@ impl MjData { macro_rules! buffer_slices_depending_on_model { ($($name:ident : [$T:ty; $size:ident $(* $lit:literal)? $(* $var:ident)?] = $description:literal;)*) => { #[allow(non_snake_case)] - impl MjData { + impl mjData { $( #[doc = $description] #[doc = "\n"] #[doc = "**SAFETY**: `model` must be exactly the same model as the one used to create this `mjData`."] - pub unsafe fn $name(&self, model: &MjModel) -> &[$T] { + pub unsafe fn $name(&self, model: &mjModel) -> &[$T] { #[cfg(debug_assertions/* size check */)] { #[allow(unnecessary_transmutes)] let _: $T = unsafe { std::mem::transmute(*self.$name) }; @@ -204,12 +204,12 @@ macro_rules! buffer_slices_depending_on_model { }; ($($name:ident / $mut_name:ident : [$T:ty; $size:ident $(* $mul:literal)?] = $description:literal;)*) => { #[allow(non_snake_case)] - impl MjData { + impl mjData { $( #[doc = $description] #[doc = "\n"] #[doc = "**SAFETY**: `model` must be exactly the same model as the one used to create this `mjData`."] - pub unsafe fn $name(&self, model: &MjModel) -> &[$T] { + pub unsafe fn $name(&self, model: &mjModel) -> &[$T] { #[cfg(debug_assertions/* size check */)] { #[allow(unnecessary_transmutes)] let _: $T = unsafe { std::mem::transmute(*self.$name) }; @@ -221,7 +221,7 @@ macro_rules! buffer_slices_depending_on_model { #[doc = $description] #[doc = "\n"] #[doc = "**SAFETY**: `model` must be exactly the same model as the one used to create this `mjData`."] - pub unsafe fn $mut_name(&mut self, model: &MjModel) -> &mut [$T] { + pub unsafe fn $mut_name(&mut self, model: &mjModel) -> &mut [$T] { #[cfg(debug_assertions/* size check */)] { #[allow(unnecessary_transmutes)] let _: $T = unsafe { std::mem::transmute(*self.$name) }; @@ -398,7 +398,7 @@ buffer_slices_depending_on_model! { macro_rules! buffer_slices { ($($name:ident : [$T:ty; $size:ident $(* $lit:literal)?] = $description:literal;)*) => { #[allow(non_snake_case)] - impl MjData { + impl mjData { $( #[doc = $description] pub fn $name(&self) -> &[$T] { diff --git a/src/types/mjmodel.rs b/src/types/mjmodel.rs index c937d0e..d0a3823 100644 --- a/src/types/mjmodel.rs +++ b/src/types/mjmodel.rs @@ -5,10 +5,10 @@ // pub use crate::bindgen::{mjModel, mjOption, mjVisual, mjStatistic}; resource_wrapper!( - MjModel for crate::bindgen::mjModel; + mjModel for crate::bindgen::mjModel; drop = crate::mj_deleteModel; ); -fields_mapping!(MjModel { +fields_mapping!(mjModel { scalars { // sizes needed at mjModel construction nq: usize = "number of generalized coordinates = dim(qpos)"; @@ -103,9 +103,9 @@ fields_mapping!(MjModel { signature: u64 = "model signature, used to detect changes in model"; } structs { - opt: mjOption = "physics options\n\n**note**: _read-only_. To dynamically mutate this, consider building `MjModel` via `MjSpec`."; - vis: mjVisual = "visualization options\n\n**note**: _read-only_. To dynamically mutate this, consider building `MjModel` via `MjSpec`."; - stat: mjStatistic = "model statistics\n\n**note**: _read-only_. To dynamically mutate this, consider building `MjModel` via `MjSpec`."; + opt: mjOption = "physics options\n\n**note**: _read-only_. To dynamically mutate this, consider building `mjModel` via `mjSpec`."; + vis: mjVisual = "visualization options\n\n**note**: _read-only_. To dynamically mutate this, consider building `mjModel` via `mjSpec`."; + stat: mjStatistic = "model statistics\n\n**note**: _read-only_. To dynamically mutate this, consider building `mjModel` via `mjSpec`."; } }); @@ -123,14 +123,14 @@ use std::{ array::from_fn as array, }; -impl MjModel { +impl mjModel { pub fn object_id(&self, name: &str) -> Option> { O::object_id(self, name) } } #[allow(non_snake_case)] -impl MjModel { +impl mjModel { /// qpos values at default pose pub fn qpos0(&self, joint_id: ObjectId) -> J::Qpos { unsafe { diff --git a/src/types/model_editing.rs b/src/types/model_editing.rs index 995bfb7..8a63af1 100644 --- a/src/types/model_editing.rs +++ b/src/types/model_editing.rs @@ -11,20 +11,20 @@ pub use crate::bindgen::{ use crate::bindgen::{mjOption, mjVisual, mjStatistic, mjString, mjLROpt}; resource_wrapper!( - MjSpec for crate::bindgen::mjSpec; + mjSpec for crate::bindgen::mjSpec; drop = crate::mj_deleteSpec; ); -impl Default for MjSpec { +impl Default for mjSpec { fn default() -> Self { crate::mjs_defaultSpec() } } -impl Clone for MjSpec { +impl Clone for mjSpec { fn clone(&self) -> Self { crate::mj_copySpec(self) } } -fields_mapping!(MjSpec { +fields_mapping!(mjSpec { boolean_flags { strippath / set_strippath = "automatically strip paths from mesh files"; hasImplicitPluginElem = "already encountered an implicit plugin sensor/actuator"; @@ -50,7 +50,7 @@ fields_mapping!(MjSpec { stat / stat_mut: mjStatistic = "statistics override (if defined)"; } }); -impl MjSpec { +impl mjSpec { /// element type, do not modify pub fn element(&self) -> &mjsElement {unsafe { &*self.element }} diff --git a/src/types/rendering.rs b/src/types/rendering.rs index 0c94f00..8423058 100644 --- a/src/types/rendering.rs +++ b/src/types/rendering.rs @@ -28,32 +28,32 @@ impl mjrRect { } resource_wrapper!( - MjrContext for crate::bindgen::mjrContext; + mjrContext for crate::bindgen::mjrContext; drop = crate::mjr_freeContext; ); -impl Default for MjrContext { +impl Default for mjrContext { /// Internally calls [`mjr_defaultContext`](crate::mjr_defaultContext). /// - /// **note**: Be sure to call [`mjr_makeContext`](crate::mjr_makeContext) for the returned `MjrContext` to allocate resources + /// **note**: Be sure to call [`mjr_makeContext`](crate::mjr_makeContext) for the returned `mjrContext` to allocate resources /// before using it in rendering. fn default() -> Self { crate::mjr_defaultContext() } } -impl MjrContext { - /// Create a new `MjrContext` with given font scale. +impl mjrContext { + /// Create a new `mjrContext` with given font scale. /// /// This internally calls: /// /// 1. [`mjr_defaultContext`](crate::mjr_defaultContext) to set default values for the scene. /// 2. [`mjr_makeContext`](crate::mjr_makeContext) to allocate resources in the scene. - pub fn new(m: &crate::MjModel, fontscale: crate::mjtFontScale) -> Self { + pub fn new(m: &crate::mjModel, fontscale: crate::mjtFontScale) -> Self { let mut con = crate::mjr_defaultContext(); crate::mjr_makeContext(m, &mut con, fontscale); con } } -fields_mapping!(MjrContext { +fields_mapping!(mjrContext { boolean_flags { glInitialized = "is OpenGL initialized"; windowAvailable = "is default/window framebuffer available"; @@ -113,7 +113,7 @@ fields_mapping!(MjrContext { } }); #[allow(non_snake_case)] -impl MjrContext { +impl mjrContext { /// default color pixel format for `mjr_readPixels` pub fn readPixelFormat(&self) -> i32 { self.readPixelFormat diff --git a/src/types/visualization.rs b/src/types/visualization.rs index 7732cc0..c4a2678 100644 --- a/src/types/visualization.rs +++ b/src/types/visualization.rs @@ -71,7 +71,7 @@ impl mjvCamera { /// Create a new free camera with default settings by [`mjv_defaultFreeCamera`](crate::mjv_defaultFreeCamera). /// /// See [`mjvCamera::default`] for a camera with default settings. - pub fn default_free(m: &crate::MjModel) -> Self { + pub fn default_free(m: &crate::mjModel) -> Self { crate::mjv_defaultFreeCamera(m) } } @@ -280,32 +280,32 @@ impl mjvOption { } resource_wrapper!( - MjvScene for crate::bindgen::mjvScene; + mjvScene for crate::bindgen::mjvScene; drop = crate::mjv_freeScene; ); -impl MjvScene { +impl mjvScene { /// Create a new abstract scene with resources allocated for `maxgeom` geoms. /// /// This internally calls: /// /// 1. [`mjv_defaultScene`](crate::mjv_defaultScene) to set default values for the scene. /// 2. [`mjv_makeScene`](crate::mjv_makeScene) to allocate resources in the scene. - pub fn new(model: &crate::MjModel, maxgeom: usize) -> Self { + pub fn new(model: &crate::mjModel, maxgeom: usize) -> Self { let mut scene = crate::mjv_defaultScene(); crate::mjv_makeScene(model, &mut scene, maxgeom); scene } } -impl Default for MjvScene { +impl Default for mjvScene { /// Internally calls [`mjv_defaultScene`](crate::mjv_defaultScene). /// - /// **note**: Be sure to call [`mjv_makeScene`](crate::mjv_makeScene) for the returned `MjvScene` + /// **note**: Be sure to call [`mjv_makeScene`](crate::mjv_makeScene) for the returned `mjvScene` /// to allocate resources in abstract scene before using it in rendering. fn default() -> Self { crate::mjv_defaultScene() } } -fields_mapping!(MjvScene { +fields_mapping!(mjvScene { scalars { maxgeom: usize = "size of allocated geom buffer"; ngeom: usize = "number of geoms currently in buffer"; @@ -326,7 +326,7 @@ fields_mapping!(MjvScene { camera: [mjvGLCamera; 2] = "left and right camera"; } }); -impl MjvScene { +impl mjvScene { fn nflexedge(&self) -> usize {self.flexedgenum().iter().sum::() as usize} fn nflexface(&self) -> usize {self.flexfacenum().iter().sum::() as usize} fn nflexvert(&self) -> usize {self.flexvertnum().iter().sum::() as usize} @@ -334,7 +334,7 @@ impl MjvScene { } macro_rules! buffer_slices { ($($name:ident : [$T:ty; $size:ident $(* $mul:literal)?] = $description:literal;)*) => { - impl MjvScene { + impl mjvScene { $( #[doc = $description] pub fn $name(&self) -> &[$T] { @@ -377,7 +377,7 @@ impl std::ops::IndexMut for RenderingFlags { &mut (unsafe { std::mem::transmute::<_, &mut [bool; mjNRNDFLAG as usize]>(&mut self.0) })[index.0 as usize] } } -impl MjvScene { +impl mjvScene { /// copy of mjVIS_FLEXVERT mjvOption flag pub fn flexvertopt(&self) -> bool {self.flexvertopt != 0} /// copy of mjVIS_FLEXEDGE mjvOption flag