rusty_mujoco 0.3.0

Rust bindings for the MuJoCo physics simulator
Documentation
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
//! # [Support](https://mujoco.readthedocs.io/en/stable/APIreference/APIfunctions.html#support)
//! 
//! These are support functions that need access to mjModel and mjData,
//! unlike the utility functions which do not need such access.
//! 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};

/// 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 {
    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,
    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,
        )
    }
}

/// 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,
    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,
        )
    }
}

/// Copy current state to the k-th model keyframe.
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<(), ()> {
    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
        > return 0 if success; 1 if buffer full.
    */
    if res == 0 {Ok(())} else {Err(())}
}

/// Determine type of friction cone.
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 {
    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 {
    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<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
}

/// 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<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
}

/// This function computes an end-effector kinematic Jacobian, describing
/// the local linear relationship between the degrees-of-freedom and
/// a given point.
/// 
/// Given a body specified by its ObjectId (body) and
/// a 3D point in the world frame (point) treated as attached to the body,
/// the Jacobian has both translational (jacp) and rotational (jacr) components.
/// 
/// <!--
///     Passing NULL for either pointer will skip that part of the computation.
/// 
///     Rust compiler's optimization will enable like `let (jacp, _) = mj_jac(...)`
///     to perform the same skipping as passing NULL.
/// -->
/// 
/// Each component is a 3-by-`nv` matrix.
/// Each row of this matrix is the gradient of the corresponding
/// coordinate of the specified point with respect to the degrees-of-freedom.
/// The frame with respect to which the Jacobian is computed is
/// centered at the body center-of-mass but aligned with the world frame.
/// 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,
    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)
}

/// 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,
    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)
}

/// Compute body center-of-mass end-effector Jacobian.
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)
}

// Compute geom end-effector Jacobian.
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)
}

/// Compute site end-effector Jacobian.
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)
}

/// Compute translation end-effector Jacobian of point, and rotation Jacobian of axis.
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)
}


/// 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,
    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)
}

/// his function computes the 3 x nv angular momentum matrix *H(q)*,
/// providing the linear mapping from generalized velocities to subtree angular momentum.
/// 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,
    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
}

/// Get id of object with the specified mjtObj type and name, returns `None` if id not found.
/// 
/// ## Example
/// 
/// ```
/// use rusty_mujoco::{mj_loadXML, mj_name2id, obj};
/// 
/// # #[cfg(false)]
/// # fn f() {
/// let model = mj_loadXML(
///     "path/to/model.xml"
/// ).unwrap();
/// # }
/// # fn example(model: &rusty_mujoco::mjModel) {
/// let body_id = mj_name2id::<obj::Body>(&model, "body_name");
/// println!("Body ID: {:?}", body_id);
/// # }
/// ```
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) })}
}

/// Get name of object with the specified mjtObj type and id, returns `None` if name not found.
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()}
}

/// Convert sparse inertia matrix M into full (i.e. dense) matrix.
/// `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: &[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
}

/// This function multiplies the joint-space inertia matrix stored in mjData.qM by a vector.
/// 
/// qM has a custom sparse format that the user should not attempt to manipulate directly.
/// Alternatively one can convert qM to a dense matrix with `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,
    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
}

/// Multiply vector by (inertia matrix)^(1/2).
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
}

/// Add inertia matrix to destination matrix.
/// 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,
    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()),
        );
    }
}

/// This function can be used to apply a Cartesian force and torque to a point on a body,
/// and add the result to the vector mjData.qfrc_applied of all applied forces.
/// Note that the function requires a pointer to this vector,
/// because sometimes we want to add the result to a different vector.
/* void mj_applyFT(
    const mjModel* m, mjData* d,
    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,
    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(),
        );
    }
}

/// Compute object 6D velocity (rot:lin) in object-centered frame, world/local orientation.
/* void mj_objectVelocity(const mjModel* m, const mjData* d,
                       int objtype, int objid, mjtNum res[6], int flg_local); */
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
}

/// Compute object 6D acceleration (rot:lin) in object-centered frame,
/// world/local orientation. If acceleration or force sensors are
/// not present in the model, mj_rnePostConstraint must be manually called
/// in order to calculate mjData.cacc – the total body acceleration,
/// including contributions from the constraint solver.
/* void mj_objectAcceleration(const mjModel* m, const mjData* d,
                           int objtype, int objid, mjtNum res[6], int flg_local); */
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
}

/// Returns the smallest signed distance between two geoms and the segment from geom1 to geom2.
/// Returned distances are bounded from above by distmax.
/// 
/// If no collision of distance smaller than distmax is found, the function will return distmax and fromto, if given, will be set to (0, 0, 0, 0, 0, 0).
/* 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,
    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)
}

/// 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,
    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
}

/// This function subtracts two vectors in the format of qpos
/// (and divides the result by dt), while respecting the properties of quaternions.
/// Recall that unit quaternions represent spatial orientations.
/// They are points on the unit sphere in 4D.
/// 
/// The tangent to that sphere is a 3D plane of rotational velocities.
/// Thus when we subtract two quaternions in the right way,
/// the result is a 3D vector and not a 4D vector.
/// Thus the output qvel has dimensionality nv while the inputs have dimensionality nq.
/*
void mj_differentiatePos(const mjModel* m, mjtNum* qvel, mjtNum dt,
                         const mjtNum* qpos1, const mjtNum* qpos2);
*/
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
}

/// 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,
    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,
        );
    }
}

/// Normalize all quaternions in qpos-type vector.
/* void mj_normalizeQuat(const mjModel* m, mjtNum* qpos); */
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());
    }
}

/// Map from body local to global Cartesian coordinates, sameframe takes values from mjtSameFrame.
/* 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,
    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,
        );
    }
}

/// Sum all body masses.
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,
    newmass: f64,
) {
    unsafe { crate::bindgen::mj_setTotalmass(m.as_mut_ptr(), newmass) }
}

/// Return a config attribute value of a plugin instance;
/// `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,
    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() })
    }
}

/// Load a dynamic library. The dynamic library is assumed to register one or more plugins.
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());
    }
}

/// Return version number: 1.0.2 is encoded as 102.
pub fn mj_version() -> u32 {
    unsafe { crate::bindgen::mj_version() as u32}
}

/// Return the current version of MuJoCo as a string.
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() }
    }
}