use crate::{mjSpec, mjsActuator, mjsDefault, mjsSensor, mjsFlex, mjsPair, mjsExclude, mjsEquality, mjsTendon, mjsWrap, mjsNumeric, mjsText, mjsTuple, mjsKey, mjsPlugin};
pub fn mjs_addActuator<'spec>(
s: &'spec mut mjSpec,
def: &mjsDefault,
) -> &'spec mut mjsActuator {
unsafe { &mut *crate::bindgen::mjs_addActuator(s.as_mut_ptr(), def) }
}
pub fn mjs_addSensor<'spec>(s: &'spec mut mjSpec) -> &'spec mut mjsSensor {
unsafe { &mut *crate::bindgen::mjs_addSensor(s.as_mut_ptr()) }
}
pub fn mjs_addFlex<'spec>(s: &'spec mut mjSpec) -> &'spec mut mjsFlex {
unsafe { &mut *crate::bindgen::mjs_addFlex(s.as_mut_ptr()) }
}
pub fn mjs_addPair<'spec>(
s: &'spec mut mjSpec,
def: &mjsDefault,
) -> &'spec mut mjsPair {
unsafe { &mut *crate::bindgen::mjs_addPair(s.as_mut_ptr(), def) }
}
pub fn mjs_addExclude<'spec>(s: &'spec mut mjSpec) -> &'spec mut mjsExclude {
unsafe { &mut *crate::bindgen::mjs_addExclude(s.as_mut_ptr()) }
}
pub fn mjs_addEquality<'spec>(
s: &'spec mut mjSpec,
def: &mjsDefault,
) -> &'spec mut mjsEquality {
unsafe { &mut *crate::bindgen::mjs_addEquality(s.as_mut_ptr(), def) }
}
pub fn mjs_addTendon<'spec>(
s: &'spec mut mjSpec,
def: &mjsDefault,
) -> &'spec mut mjsTendon {
unsafe { &mut *crate::bindgen::mjs_addTendon(s.as_mut_ptr(), def) }
}
pub fn mjs_wrapSite<'tendon>(
tendon: &'tendon mut mjsTendon,
name: &str,
) -> &'tendon mut mjsWrap {
let c_name = std::ffi::CString::new(name).expect("`name` must not contain null bytes");
unsafe { &mut *crate::bindgen::mjs_wrapSite(tendon, c_name.as_ptr()) }
}
pub fn mjs_wrapGeom<'tendon>(
tendon: &'tendon mut mjsTendon,
name: &str,
sidesite: &str,
) -> &'tendon mut mjsWrap {
let c_name = std::ffi::CString::new(name).expect("`name` must not contain null bytes");
let c_sidesite = std::ffi::CString::new(sidesite).expect("`sidesite` must not contain null bytes");
unsafe { &mut *crate::bindgen::mjs_wrapGeom(tendon, c_name.as_ptr(), c_sidesite.as_ptr()) }
}
pub fn mjs_wrapJoint<'tendon>(
tendon: &'tendon mut mjsTendon,
name: &str,
coef: f64,
) -> &'tendon mut mjsWrap {
let c_name = std::ffi::CString::new(name).expect("`name` must not contain null bytes");
unsafe { &mut *crate::bindgen::mjs_wrapJoint(tendon, c_name.as_ptr(), coef) }
}
pub fn mjs_wrapPulley<'tendon>(
tendon: &'tendon mut mjsTendon,
divisor: f64,
) -> &'tendon mut mjsWrap {
unsafe { &mut *crate::bindgen::mjs_wrapPulley(tendon, divisor) }
}
pub fn mjs_addNumeric<'spec>(s: &'spec mut mjSpec) -> &'spec mut mjsNumeric {
unsafe { &mut *crate::bindgen::mjs_addNumeric(s.as_mut_ptr()) }
}
pub fn mjs_addText<'spec>(s: &'spec mut mjSpec) -> &'spec mut mjsText {
unsafe { &mut *crate::bindgen::mjs_addText(s.as_mut_ptr()) }
}
pub fn mjs_addTuple<'spec>(s: &'spec mut mjSpec) -> &'spec mut mjsTuple {
unsafe { &mut *crate::bindgen::mjs_addTuple(s.as_mut_ptr()) }
}
pub fn mjs_addKey<'spec>(s: &'spec mut mjSpec) -> &'spec mut mjsKey {
unsafe { &mut *crate::bindgen::mjs_addKey(s.as_mut_ptr()) }
}
pub fn mjs_addPlugin<'spec>(s: &'spec mut mjSpec) -> &'spec mut mjsPlugin {
unsafe { &mut *crate::bindgen::mjs_addPlugin(s.as_mut_ptr()) }
}
pub fn mjs_addDefault<'spec>(
s: &'spec mut mjSpec,
classname: &str,
parent: &mjsDefault,
) -> &'spec mut mjsDefault {
let c_classname = std::ffi::CString::new(classname).expect("`classname` must not contain null bytes");
unsafe { &mut *crate::bindgen::mjs_addDefault(s.as_mut_ptr(), c_classname.as_ptr(), parent) }
}