Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion Cargo.toml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
[package]
name = "rusty_mujoco"
version = "0.2.0"
version = "0.1.1"
edition = "2024"
authors = ["kanarus <kanarus786@gmail.com>"]
documentation = "https://docs.rs/rusty_mujoco"
Expand Down
10 changes: 2 additions & 8 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@
*Cargo.toml*
```toml
[dependencies]
rusty_mujoco = "0.2"
rusty_mujoco = "0.1"
```

*src/main.rs*
Expand All @@ -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

Expand Down
6 changes: 3 additions & 3 deletions examples/visualize_left_object.rs
Original file line number Diff line number Diff line change
@@ -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,
Expand Down Expand Up @@ -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")));

Expand Down
12 changes: 6 additions & 6 deletions src/functions/assets.rs
Original file line number Diff line number Diff line change
@@ -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) }
Expand Down
6 changes: 3 additions & 3 deletions src/functions/attachment.rs
Original file line number Diff line number Diff line change
@@ -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,
Expand Down Expand Up @@ -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<(), ()> {
/*
<https://mujoco.readthedocs.io/en/stable/APIreference/APIfunctions.html#mjs-detachbody>
> return 0 on success
Expand All @@ -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<(), ()> {
/*
<https://mujoco.readthedocs.io/en/stable/APIreference/APIfunctions.html#mjs-detachdefault>
> return 0 on success
Expand Down
24 changes: 12 additions & 12 deletions src/functions/components.rs
Original file line number Diff line number Diff line change
Expand Up @@ -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()) }
}
6 changes: 3 additions & 3 deletions src/functions/element_initialization.rs
Original file line number Diff line number Diff line change
@@ -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,
Expand All @@ -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::<crate::bindgen::mjSpec>::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.
Expand Down
6 changes: 3 additions & 3 deletions src/functions/error_and_memory.rs
Original file line number Diff line number Diff line change
Expand Up @@ -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,
) {
Expand All @@ -54,7 +54,7 @@ pub fn mju_writeLog(kind: impl Into<String>, msg: impl Into<String>) {

/// Get compiler error message from spec.
/* const char* mjs_getError(mjSpec* s); */
pub fn mjs_getError(s: &mut crate::MjSpec) -> Option<String> {
pub fn mjs_getError(s: &mut crate::mjSpec) -> Option<String> {
let c_ptr = unsafe { crate::bindgen::mjs_getError(s.as_mut_ptr()) };
if c_ptr.is_null() {
None
Expand All @@ -65,7 +65,7 @@ pub fn mjs_getError(s: &mut crate::MjSpec) -> Option<String> {

/// 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 {
/*
<https://mujoco.readthedocs.io/en/stable/APIreference/APIfunctions.html#mjs-isWarning>
> Returns 1 if the error is a warning.
Expand Down
24 changes: 12 additions & 12 deletions src/functions/find_and_get_utilities.rs
Original file line number Diff line number Diff line change
@@ -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<MjSpec> {
pub fn mjs_getSpec(element: &mut mjsElement) -> Option<mjSpec> {
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<MjSpec> {
pub fn mjs_findSpec<'spec>(spec: &'spec mut mjSpec, name: &str) -> Option<mjSpec> {
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 }) }
Expand All @@ -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> {
Expand Down Expand Up @@ -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 }) }
Expand All @@ -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");
Expand All @@ -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 })}
}
Expand Down Expand Up @@ -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_) };
Expand All @@ -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) };
Expand Down
Loading