use crate::{obj, mjContact, mjData, mjModel, ObjectId};
pub fn mj_stateSize(m: &mjModel, spec: crate::bindgen::mjtState) -> usize {
unsafe { crate::bindgen::mj_stateSize(m.as_ptr(), spec.0 as u32) as _ }
}
pub fn mj_getState(
m: &mjModel,
d: &mjData,
state: &mut [f64],
spec: crate::bindgen::mjtState,
) {
#[cfg(debug_assertions)] {
assert_eq!(state.len(), mj_stateSize(m, spec));
}
unsafe {
crate::bindgen::mj_getState(
m.as_ptr(),
d.as_ptr(),
state.as_mut_ptr(),
spec.0 as u32,
)
}
}
pub fn mj_setState(
m: &mjModel,
d: &mut mjData,
state: &[f64],
spec: crate::bindgen::mjtState,
) {
#[cfg(debug_assertions)] {
assert_eq!(state.len(), mj_stateSize(m, spec));
}
unsafe {
crate::bindgen::mj_setState(
m.as_ptr(),
d.as_mut_ptr(),
state.as_ptr(),
spec.0 as u32,
)
}
}
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) }
}
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) };
if res == 0 {Ok(())} else {Err(())}
}
pub fn mj_isPyramidal(m: &mjModel) -> bool {
unsafe { crate::bindgen::mj_isPyramidal(m.as_ptr()) != 0 }
}
pub fn mj_isSparse(m: &mjModel) -> bool {
unsafe { crate::bindgen::mj_isSparse(m.as_ptr()) != 0 }
}
pub fn mj_isDual(m: &mjModel) -> bool {
unsafe { crate::bindgen::mj_isDual(m.as_ptr()) != 0 }
}
pub fn mj_mulJacVec(m: &mjModel, d: &mjData, mut vec: Vec<f64>) -> Vec<f64> {
#[cfg(debug_assertions)] {
assert_eq!(vec.len(), m.nv());
}
let mut res = vec![0.0; d.nefc()];
unsafe {
crate::bindgen::mj_mulJacVec(
m.as_ptr(),
d.as_ptr(),
vec.as_mut_ptr(),
res.as_mut_ptr(),
);
}
res
}
pub fn mj_mulJacTVec(m: &mjModel, d: &mjData, mut vec: Vec<f64>) -> Vec<f64> {
#[cfg(debug_assertions)] {
assert_eq!(vec.len(), d.nefc());
}
let mut res = vec![0.0; m.nv()];
unsafe {
crate::bindgen::mj_mulJacTVec(
m.as_ptr(),
d.as_ptr(),
vec.as_mut_ptr(),
res.as_mut_ptr(),
);
}
res
}
pub fn mj_jac(
m: &mjModel,
d: &mjData,
body: ObjectId<obj::Body>,
point: [f64; 3],
) -> (Vec<f64>, Vec<f64>) {
let mut jacp = vec![0.0; 3 * m.nv() as usize];
let mut jacr = vec![0.0; 3 * m.nv() as usize];
unsafe {
crate::bindgen::mj_jac(
m.as_ptr(),
d.as_ptr(),
jacp.as_mut_ptr(),
jacr.as_mut_ptr(),
&point,
body.index() as i32,
);
}
(jacp, jacr)
}
pub fn mj_jacBody(
m: &mjModel,
d: &mjData,
body: ObjectId<obj::Body>,
) -> (Vec<f64>, Vec<f64>) {
let mut jacp = vec![0.0; 3 * m.nv() as usize];
let mut jacr = vec![0.0; 3 * m.nv() as usize];
unsafe {
crate::bindgen::mj_jacBody(
m.as_ptr(),
d.as_ptr(),
jacp.as_mut_ptr(),
jacr.as_mut_ptr(),
body.index() as i32,
)
};
(jacp, jacr)
}
pub fn mj_jacBodyCom(
m: &mjModel,
d: &mjData,
body: ObjectId<obj::Body>,
) -> (Vec<f64>, Vec<f64>) {
let mut jacp = vec![0.0; 3 * m.nv() as usize];
let mut jacr = vec![0.0; 3 * m.nv() as usize];
unsafe {
crate::bindgen::mj_jacBodyCom(
m.as_ptr(),
d.as_ptr(),
jacp.as_mut_ptr(),
jacr.as_mut_ptr(),
body.index() as i32,
)
};
(jacp, jacr)
}
pub fn mj_jacGeom(
m: &mjModel,
d: &mjData,
geom: ObjectId<obj::Geom>,
) -> (Vec<f64>, Vec<f64>) {
let mut jacp = vec![0.0; 3 * m.nv() as usize];
let mut jacr = vec![0.0; 3 * m.nv() as usize];
unsafe {
crate::bindgen::mj_jacGeom(
m.as_ptr(),
d.as_ptr(),
jacp.as_mut_ptr(),
jacr.as_mut_ptr(),
geom.index() as i32,
)
};
(jacp, jacr)
}
pub fn mj_jacSite(
m: &mjModel,
d: &mjData,
site: ObjectId<obj::Site>,
) -> (Vec<f64>, Vec<f64>) {
let mut jacp = vec![0.0; 3 * m.nv() as usize];
let mut jacr = vec![0.0; 3 * m.nv() as usize];
unsafe {
crate::bindgen::mj_jacSite(
m.as_ptr(),
d.as_ptr(),
jacp.as_mut_ptr(),
jacr.as_mut_ptr(),
site.index() as i32,
)
};
(jacp, jacr)
}
pub fn mj_jacPointAxis(
m: &mjModel,
d: &mut mjData,
body: ObjectId<obj::Body>,
point: [f64; 3],
axis: [f64; 3],
) -> (Vec<f64>, Vec<f64>) {
let mut jacp = vec![0.0; 3 * m.nv() as usize];
let mut jacr = vec![0.0; 3 * m.nv() as usize];
unsafe {
crate::bindgen::mj_jacPointAxis(
m.as_ptr(),
d.as_mut_ptr(),
jacp.as_mut_ptr(),
jacr.as_mut_ptr(),
&point,
&axis,
body.index() as i32,
)
};
(jacp, jacr)
}
pub fn mj_jacDot(
m: &mjModel,
d: &mjData,
body: ObjectId<obj::Body>,
point: [f64; 3],
) -> (Vec<f64>, Vec<f64>) {
let mut jacp = vec![0.0; 3 * m.nv() as usize];
let mut jacr = vec![0.0; 3 * m.nv() as usize];
unsafe {
crate::bindgen::mj_jacDot(
m.as_ptr(),
d.as_ptr(),
jacp.as_mut_ptr(),
jacr.as_mut_ptr(),
&point,
body.index() as i32,
)
};
(jacp, jacr)
}
pub fn mj_angmomMat(
m: &mjModel,
d: &mut mjData,
body: ObjectId<obj::Body>,
) -> Vec<f64> {
let mut res = vec![0.0; 3 * m.nv()];
unsafe {
crate::bindgen::mj_angmomMat(
m.as_ptr(),
d.as_mut_ptr(),
res.as_mut_ptr(),
body.index() as i32,
)
};
res
}
pub fn mj_name2id<O: crate::Obj>(
m: &mjModel,
name: &str,
) -> Option<ObjectId<O>> {
let c_name = std::ffi::CString::new(name).expect("`name` contains null bytes");
let index = unsafe {
crate::bindgen::mj_name2id(m.as_ptr(), O::TYPE.0 as i32, c_name.as_ptr())
};
if index < 0 {None} else {Some(unsafe { ObjectId::<O>::new_unchecked(index as usize) })}
}
pub fn mj_id2name<O: crate::Obj>(
m: &mjModel,
id: ObjectId<O>,
) -> String {
let c_name = unsafe {
crate::bindgen::mj_id2name(m.as_ptr(), O::TYPE.0 as i32, id.index() as i32)
};
#[cfg(debug_assertions)] {
assert!(!c_name.is_null(), "`ObjectId` is always expected to have a valid index for the corresponding object type");
}
unsafe {std::ffi::CStr::from_ptr(c_name).to_str().unwrap().to_owned()}
}
pub fn mj_fullM(
m: &mjModel,
M: &[f64],
) -> Vec<f64> {
#[cfg(debug_assertions)] {
assert_eq!(M.len(), m.nM());
}
let mut res = vec![0.0; m.nv() * m.nv()];
unsafe {
crate::bindgen::mj_fullM(
m.as_ptr(),
res.as_mut_ptr(),
M.as_ptr(),
);
}
res
}
pub fn mj_mulM(
m: &mjModel,
d: &mjData,
mut vec: Vec<f64>,
) -> Vec<f64> {
#[cfg(debug_assertions)] {
assert_eq!(vec.len(), m.nv());
}
let mut res = vec![0.0; m.nv()];
unsafe {
crate::bindgen::mj_mulM(
m.as_ptr(),
d.as_ptr(),
vec.as_mut_ptr(),
res.as_mut_ptr(),
);
}
res
}
pub fn mj_mulM2(
m: &mjModel,
d: &mjData,
mut vec: Vec<f64>,
) -> Vec<f64> {
#[cfg(debug_assertions)] {
assert_eq!(vec.len(), m.nv());
}
let mut res = vec![0.0; m.nv()];
unsafe {
crate::bindgen::mj_mulM2(
m.as_ptr(),
d.as_ptr(),
vec.as_mut_ptr(),
res.as_mut_ptr(),
);
}
res
}
pub fn mj_addM(
m: &mjModel,
d: &mut mjData,
dst: &mut [f64],
rownnz: Option<&mut [i32]>,
rowadr: Option<&mut [i32]>,
colind: Option<&mut [i32]>,
) {
#[cfg(debug_assertions)] {
match (rownnz.as_ref(), rowadr.as_ref(), colind.as_ref()) {
(Some(rownnz), Some(rowadr), Some(_)) => {
assert_eq!(rownnz.len(), m.nv());
assert_eq!(rowadr.len(), m.nv());
}
(None, None, None) => {
assert_eq!(dst.len(), m.nv() * m.nv());
}
_ => panic!("If any of rownnz, rowadr or colind is specified, all must be specified"),
}
}
unsafe {
crate::bindgen::mj_addM(
m.as_ptr(),
d.as_mut_ptr(),
dst.as_mut_ptr(),
rownnz.map_or(std::ptr::null_mut(), |x| x.as_mut_ptr()),
rowadr.map_or(std::ptr::null_mut(), |x| x.as_mut_ptr()),
colind.map_or(std::ptr::null_mut(), |x| x.as_mut_ptr()),
);
}
}
pub fn mj_applyFT(
m: &mjModel,
d: &mut mjData,
body: ObjectId<obj::Body>,
point: [f64; 3],
force: [f64; 3],
torque: [f64; 3],
qfrc_target: &mut [f64],
) {
unsafe {
crate::bindgen::mj_applyFT(
m.as_ptr(),
d.as_mut_ptr(),
&point,
&force,
&torque,
body.index() as i32,
qfrc_target.as_mut_ptr(),
);
}
}
pub fn mj_objectVelocity<O: crate::id::Obj>(
m: &mjModel,
d: &mjData,
object: ObjectId<O>,
local: bool,
) -> [f64; 6] {
let mut res = [0.0; 6];
unsafe {
crate::bindgen::mj_objectVelocity(
m.as_ptr(),
d.as_ptr(),
O::TYPE.0 as i32,
object.index() as i32,
&mut res,
local as i32,
);
}
res
}
pub fn mj_objectAcceleration<O: crate::id::Obj>(
m: &mjModel,
d: &mjData,
object: ObjectId<O>,
local: bool,
) -> [f64; 6] {
let mut res = [0.0; 6];
unsafe {
crate::bindgen::mj_objectAcceleration(
m.as_ptr(),
d.as_ptr(),
O::TYPE.0 as i32,
object.index() as i32,
&mut res,
local as i32,
);
}
res
}
pub fn mj_geomDistance(
m: &mjModel,
d: &mjData,
geom1: ObjectId<obj::Geom>,
geom2: ObjectId<obj::Geom>,
distmax: f64,
) -> (f64, [f64; 6]) {
let mut fromto = [0.0; 6];
let dist = unsafe {
crate::bindgen::mj_geomDistance(
m.as_ptr(),
d.as_ptr(),
geom1.index() as i32,
geom2.index() as i32,
distmax,
&mut fromto,
)
};
(dist, fromto)
}
pub fn mj_contactForce(
m: &mjModel,
d: &mjData,
contact_id: usize,
) -> [f64; 6] {
let mut result = [0.0; 6];
unsafe {
crate::bindgen::mj_contactForce(
m.as_ptr(),
d.as_ptr(),
contact_id as i32,
&mut result,
);
}
result
}
pub fn mj_differentiatePos(
m: &mjModel,
qpos1: &[f64],
qpos2: &[f64],
dt: f64,
) -> Vec<f64> {
#[cfg(debug_assertions)] {
assert_eq!(qpos1.len(), m.nq());
assert_eq!(qpos2.len(), m.nq());
}
let mut qvel = vec![0.0; m.nv()];
unsafe {
crate::bindgen::mj_differentiatePos(
m.as_ptr(),
qvel.as_mut_ptr(),
dt,
qpos1.as_ptr(),
qpos2.as_ptr(),
);
}
qvel
}
pub fn mj_integratePos(
m: &mjModel,
qpos: &mut [f64],
qvel: &[f64],
dt: f64,
) {
#[cfg(debug_assertions)] {
assert_eq!(qpos.len(), m.nq());
assert_eq!(qvel.len(), m.nv());
}
unsafe {
crate::bindgen::mj_integratePos(
m.as_ptr(),
qpos.as_mut_ptr(),
qvel.as_ptr(),
dt,
);
}
}
pub fn mj_normalizeQuat(
m: &mjModel,
qpos: &mut [f64],
) {
#[cfg(debug_assertions)] {
assert_eq!(qpos.len(), m.nq());
}
unsafe {
crate::bindgen::mj_normalizeQuat(m.as_ptr(), qpos.as_mut_ptr());
}
}
pub fn mj_local2Global(
d: &mut mjData,
xpos: &mut [f64; 3],
xmat: &mut [f64; 9],
pos: &[f64; 3],
quat: &[f64; 4],
body: ObjectId<obj::Body>,
sameframe: crate::bindgen::mjtSameFrame,
) {
unsafe {
crate::bindgen::mj_local2Global(
d.as_mut_ptr(),
xpos,
xmat,
pos,
quat,
body.index() as i32,
sameframe.0 as u8,
);
}
}
pub fn mj_getTotalmass(m: &mjModel) -> f64 {
unsafe { crate::bindgen::mj_getTotalmass(m.as_ptr()) }
}
pub fn mj_setTotalmass(
m: &mut mjModel,
newmass: f64,
) {
unsafe { crate::bindgen::mj_setTotalmass(m.as_mut_ptr(), newmass) }
}
pub fn mj_getPluginConfig(
m: &mjModel,
plugin_id: ObjectId<obj::Plugin>,
attrib: &str,
) -> Option<String> {
let c_attrib = std::ffi::CString::new(attrib).expect("`attrib` contains null bytes");
let c_str = unsafe {
crate::bindgen::mj_getPluginConfig(m.as_ptr(), plugin_id.index() as i32, c_attrib.as_ptr())
};
if c_str.is_null() {
None
} else {
Some(unsafe { std::ffi::CStr::from_ptr(c_str).to_str().unwrap().to_owned() })
}
}
pub fn mj_loadPluginLibrary(
path: &str,
) {
let c_path = std::ffi::CString::new(path).expect("`path` contains null bytes");
unsafe {
crate::bindgen::mj_loadPluginLibrary(c_path.as_ptr());
}
}
pub fn mj_version() -> u32 {
unsafe { crate::bindgen::mj_version() as u32}
}
pub fn mj_versionString() -> String {
let c_str = unsafe { crate::bindgen::mj_versionString() };
if c_str.is_null() {
String::new()
} else {
unsafe { std::ffi::CStr::from_ptr(c_str).to_str().unwrap().to_owned() }
}
}