use crate::{
mjSpec,
mjsElement, mjsBody, mjsFrame, mjsDefault,
mjtObj,
};
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)) }
}
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)) }
}
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 }) }
}
pub fn mjs_findElement<'spec>(
spec: &'spec mut mjSpec,
type_: mjtObj,
name: &str,
) -> Option<&'spec mut mjsElement> {
let name = std::ffi::CString::new(name).expect("`name` must not contain null bytes");
let ptr = unsafe { crate::bindgen::mjs_findElement(spec.as_mut_ptr(), type_, name.as_ptr()) };
if ptr.is_null() {None} else {Some(unsafe { &mut *ptr }) }
}
pub fn mjs_findChild<'body>(body: &'body mut mjsBody, name: &str) -> Option<&'body mut mjsBody> {
let name = std::ffi::CString::new(name).expect("`name` must not contain null bytes");
let ptr = unsafe { crate::bindgen::mjs_findChild(body, name.as_ptr()) };
if ptr.is_null() {None} else {Some(unsafe { &mut *ptr }) }
}
pub fn mjs_getParent<'body>(element: &'body mut mjsElement) -> Option<&'body mut mjsBody> {
let ptr = unsafe { crate::bindgen::mjs_getParent(element) };
if ptr.is_null() {None} else {Some(unsafe { &mut *ptr }) }
}
pub fn mjs_getFrame<'element>(element: &'element mut mjsElement) -> Option<&'element mut mjsFrame> {
let ptr = unsafe { crate::bindgen::mjs_getFrame(element) };
if ptr.is_null() {None} else {Some(unsafe { &mut *ptr }) }
}
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 }) }
}
pub fn mjs_getDefault<'element>(element: &'element mut mjsElement) -> Option<&'element mut mjsDefault> {
let ptr = unsafe { crate::bindgen::mjs_getDefault(element) };
if ptr.is_null() {None} else {Some(unsafe { &mut *ptr }) }
}
pub fn mjs_findDefault<'spec>(
spec: &'spec mut mjSpec,
classname: &str,
) -> Option<&'spec mut mjsDefault> {
let classname = std::ffi::CString::new(classname).expect("`classname` must not contain null bytes");
let ptr = unsafe { crate::bindgen::mjs_findDefault(spec.as_mut_ptr(), classname.as_ptr()) };
if ptr.is_null() {None} else {Some(unsafe { &mut *ptr }) }
}
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 })}
}
pub fn mjs_getId(element: &mut mjsElement) -> usize {
unsafe { crate::bindgen::mjs_getId(element) as usize }
}
pub fn mjs_firstChild<'body>(
body: &'body mut mjsBody,
type_: mjtObj,
recurse: bool,
) -> Option<&'body mut mjsElement> {
let ptr = unsafe { crate::bindgen::mjs_firstChild(body, type_, recurse as i32) };
if ptr.is_null() {None} else {Some(unsafe { &mut *ptr }) }
}
pub fn mjs_nextChild<'body>(
body: &'body mut mjsBody,
child: &mut mjsElement,
recurse: bool,
) -> Option<&'body mut mjsElement> {
let ptr = unsafe { crate::bindgen::mjs_nextChild(body, child, recurse as i32) };
if ptr.is_null() {None} else {Some(unsafe { &mut *ptr }) }
}
pub fn mjs_firstElement<'spec>(
spec: &'spec mut mjSpec,
type_: mjtObj,
) -> Option<&'spec mut mjsElement> {
let ptr = unsafe { crate::bindgen::mjs_firstElement(spec.as_mut_ptr(), type_) };
if ptr.is_null() {None} else {Some(unsafe { &mut *ptr }) }
}
pub fn mjs_nextElement<'spec>(
spec: &'spec mut mjSpec,
element: &mut mjsElement,
) -> Option<&'spec mut mjsElement> {
let ptr = unsafe { crate::bindgen::mjs_nextElement(spec.as_mut_ptr(), element) };
if ptr.is_null() {None} else {Some(unsafe { &mut *ptr }) }
}