mujoco-rs 5.0.0+mj-3.9.0

A high-level Rust wrapper around the MuJoCo C library, with a native viewer (re-)written in Rust.
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
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
1001
1002
1003
1004
1005
1006
1007
1008
1009
1010
1011
1012
1013
1014
1015
1016
1017
1018
1019
1020
1021
1022
1023
1024
1025
1026
1027
1028
1029
1030
1031
1032
1033
1034
1035
1036
1037
1038
1039
1040
1041
1042
1043
1044
1045
1046
1047
1048
1049
1050
1051
1052
1053
1054
1055
1056
1057
1058
1059
1060
1061
1062
1063
1064
1065
1066
1067
1068
1069
1070
1071
1072
1073
1074
1075
1076
1077
1078
1079
1080
1081
1082
1083
1084
1085
1086
1087
1088
1089
1090
1091
1092
1093
1094
1095
1096
1097
1098
1099
1100
1101
1102
1103
1104
1105
1106
1107
1108
1109
1110
1111
1112
1113
1114
1115
1116
1117
1118
1119
1120
1121
1122
1123
1124
1125
1126
1127
1128
1129
1130
1131
1132
1133
1134
1135
1136
1137
1138
1139
1140
1141
1142
1143
1144
1145
1146
1147
1148
1149
1150
1151
1152
1153
1154
1155
1156
1157
1158
1159
1160
1161
1162
1163
1164
1165
1166
1167
1168
1169
1170
1171
1172
1173
1174
1175
1176
1177
1178
1179
1180
1181
1182
1183
1184
1185
1186
1187
1188
1189
1190
1191
1192
1193
1194
1195
1196
1197
1198
1199
1200
1201
1202
1203
1204
1205
1206
1207
1208
1209
1210
1211
1212
1213
1214
1215
1216
1217
1218
1219
1220
1221
1222
1223
1224
1225
1226
1227
1228
1229
1230
1231
1232
1233
1234
1235
1236
1237
1238
1239
1240
1241
1242
1243
1244
1245
1246
1247
1248
1249
1250
1251
1252
1253
1254
1255
1256
1257
1258
1259
1260
1261
1262
1263
1264
1265
1266
1267
1268
1269
1270
1271
1272
1273
//! Definitions related to visualization.
use std::default::Default;
use std::mem::MaybeUninit;
use std::ops::Deref;
use std::ptr;

use super::mj_rendering::{MjrContext, MjrRectangle};
use super::mj_primitive::{MjtNum, MjtByte, MjtSize};
use super::mj_model::{MjModel, MjtGeom};
use super::mj_data::MjData;
use crate::{array_slice_dyn, c_str_as_str_method};
use crate::error::MjSceneError;
use crate::getter_setter;
use crate::mujoco_c::*;

/// Result of a mouse-based selection query via [`MjvScene::find_selection`].
#[derive(Debug, Clone, PartialEq)]
pub struct SceneSelection {
    /// Selected body id, or `None` if nothing was selected.
    pub body_id: Option<usize>,
    /// Selected geom id, or `None` if nothing was selected.
    pub geom_id: Option<usize>,
    /// Selected flex id, or `None` if nothing was selected.
    pub flex_id: Option<usize>,
    /// Selected skin id, or `None` if nothing was selected.
    pub skin_id: Option<usize>,
    /// 3D world coordinates of the selection point.
    pub point: [MjtNum; 3],
}

impl Default for SceneSelection {
    fn default() -> Self {
        Self {
            body_id: None,
            geom_id: None,
            flex_id: None,
            skin_id: None,
            point: [0.0; 3],
        }
    }
}

/* Types */
/// These are the available categories of geoms in the abstract visualizer. The bitmask can be used in the function
/// `mjr_render` to specify which categories should be rendered.
pub type MjtCatBit = mjtCatBit;

/// These are the mouse actions that the abstract visualizer recognizes. It is up to the user to intercept mouse events
/// and translate them into these actions, as illustrated in `simulate.cc <saSimulate>`.
pub type MjtMouse = mjtMouse;

/// These bitmasks enable the translational and rotational components of the mouse perturbation. For the regular mouse,
/// only one can be enabled at a time. For the 3D mouse (SpaceNavigator) both can be enabled simultaneously. They are used
/// in `mjvPerturb.active`.
pub type MjtPertBit = mjtPertBit;

/// These are the possible camera types, used in `mjvCamera.type`.
pub type MjtCamera = mjtCamera;

// Compile-time verification that TryFrom discriminant values match the actual enum variants.
const _: () = {
    assert!(MjtCamera::mjCAMERA_FREE as i32 == 0);
    assert!(MjtCamera::mjCAMERA_TRACKING as i32 == 1);
    assert!(MjtCamera::mjCAMERA_FIXED as i32 == 2);
    assert!(MjtCamera::mjCAMERA_USER as i32 == 3);
};

impl TryFrom<i32> for MjtCamera {
    type Error = MjSceneError;
    fn try_from(value: i32) -> Result<Self, Self::Error> {
        match value {
            0 => Ok(Self::mjCAMERA_FREE),
            1 => Ok(Self::mjCAMERA_TRACKING),
            2 => Ok(Self::mjCAMERA_FIXED),
            3 => Ok(Self::mjCAMERA_USER),
            _ => Err(MjSceneError::InvalidCameraType(value))
        }
    }
}

/// These are the abstract visualization elements that can have text labels. Used in `mjvOption.label`.
pub type MjtLabel = mjtLabel;

/// These are the MuJoCo objects whose spatial frames can be rendered. Used in `mjvOption.frame`.
pub type MjtFrame = mjtFrame;

/// These are indices in the array `mjvOption.flags`, whose elements enable/disable the visualization of the
/// corresponding model or decoration element.
pub type MjtVisFlag = mjtVisFlag;

/// These are indices in the array `mjvScene.flags`, whose elements enable/disable OpenGL rendering effects.
pub type MjtRndFlag = mjtRndFlag;

/// These are the possible stereo rendering types. They are used in `mjvScene.stereo`.
pub type MjtStereo = mjtStereo;
/**********************************************************************************************************************/

/***********************************************************************************************************************
** MjvPerturb
***********************************************************************************************************************/
/// Mouse perturbation state (selected body/flex/skin, interaction mode, reference position/orientation, local position).
pub type MjvPerturb = mjvPerturb;
impl Default for MjvPerturb {
    fn default() -> Self {
        // SAFETY: mjv_defaultPerturb initializes all fields to valid defaults;
        // the MaybeUninit pointer is valid and aligned.
        unsafe {
            let mut pert = MaybeUninit::uninit();
            mjv_defaultPerturb(pert.as_mut_ptr());
            pert.assume_init()
        }
    }
}

impl MjvPerturb {
    /// Initializes the perturbation state for mouse interaction of the given `type_`.
    /// Must be called before [`MjvPerturb::move_`].
    pub fn start<M: Deref<Target = MjModel>>(&mut self, type_: MjtPertBit, data: &mut MjData<M>, scene: &MjvScene) {
        let model_ffi = data.model().ffi();
        unsafe { mjv_initPerturb(model_ffi, data.ffi_mut(), scene.ffi(), self); }
        self.active = type_ as i32;
    }

    /// Move an object with mouse. This is a wrapper around `mjv_movePerturb`.
    ///
    /// # Panics
    /// Panics if `self.select` is out of range for the model in `data` (i.e. negative or
    /// `>= nbody`).
    pub fn move_<M: Deref<Target = MjModel>>(&mut self, data: &MjData<M>, action: MjtMouse, dx: MjtNum, dy: MjtNum, scene: &MjvScene) {
        // mjv_movePerturb dereferences d->xmat + 9*select (move-relative actions) and
        // d->xquat + 4*select / m->body_iquat + 4*select (rotate actions) *before* its own
        // sel range check, so an out-of-range id is an out-of-bounds read. Unlike the
        // mjv_updateScene path, the C function has no `select <= 0` early-out either, so the
        // negative case must be rejected here too.
        let nbody = data.model().nbody();
        assert!(
            self.select >= 0 && (self.select as MjtSize) < nbody,
            "selected perturbation body id {} is out of range for a model with {} bodies",
            self.select, nbody
        );
        unsafe { mjv_movePerturb(data.model().ffi(), data.ffi(), action as i32, dx, dy, scene.ffi(), self); }
    }

    /// Apply perturbation pose and force.
    ///
    /// # Note
    /// This method **zeroes `xfrc_applied`** for all bodies before applying the perturbation
    /// force. Any external forces set on `data` before calling this method will be cleared.
    /// If you need to preserve external forces, apply them *after* calling this method.
    pub fn apply<M: Deref<Target = MjModel>>(&mut self, data: &mut MjData<M>) {
        data.xfrc_applied_mut().fill([0.0; 6]);
        let model_ffi = data.model().ffi();
        unsafe { mjv_applyPerturbPose(model_ffi, data.ffi_mut(), self, 0); }
        let model_ffi = data.model().ffi();
        unsafe { mjv_applyPerturbForce(model_ffi, data.ffi_mut(), self); }
    }

    /// Updates the body-local position of the selection point.
    ///
    /// # Panics
    /// Panics if `self.select` is out of range for the `xpos`/`xmat` arrays (i.e., negative or
    /// `>= nbody`). In debug builds, a dedicated assertion fires first for the negative case.
    pub fn update_local_pos<M: Deref<Target = MjModel>>(&mut self, selection_xyz: &[MjtNum; 3], data: &MjData<M>) {
        debug_assert!(self.select >= 0, "invalid selecting when calling update_local_pos");
        let select = self.select as usize;
        let body_xpos = &data.xpos()[select];
        let body_xmat = &data.xmat()[select];
        // Inverse transform into the local frame of the body.
        // mju_sub3 equivalent
        let tmp = [
            selection_xyz[0] - body_xpos[0],
            selection_xyz[1] - body_xpos[1],
            selection_xyz[2] - body_xpos[2],
        ];
        // mju_mulMatTVec3 equivalent (mat is row-major 3x3)
        self.localpos = [
            body_xmat[0] * tmp[0] + body_xmat[3] * tmp[1] + body_xmat[6] * tmp[2],
            body_xmat[1] * tmp[0] + body_xmat[4] * tmp[1] + body_xmat[7] * tmp[2],
            body_xmat[2] * tmp[0] + body_xmat[5] * tmp[1] + body_xmat[8] * tmp[2],
        ];
    }
}



/***********************************************************************************************************************
** MjvCamera
***********************************************************************************************************************/
/// Abstract camera parameters (type, fixed/tracking ids, lookat, distance, azimuth, elevation, orthographic mode).
pub type MjvCamera = mjvCamera;
impl MjvCamera {
    /// Creates a new free camera.
    /// By default, the camera will look at the center of the model.
    pub fn new_free(model: &MjModel) -> Self {
        let mut camera: mjvCamera_ = Self::default();
        unsafe { mjv_defaultFreeCamera(model.ffi(), &mut camera); }
        camera
    }

    /// Creates a new fixed camera.
    ///
    /// # Panics
    /// In debug builds, panics if `camera_id` exceeds `i32::MAX`.
    pub fn new_fixed(camera_id: usize) -> Self {
        debug_assert!(camera_id <= i32::MAX as usize, "camera_id exceeds i32::MAX");
        mjvCamera_ {
            type_: MjtCamera::mjCAMERA_FIXED as i32,
            fixedcamid: camera_id as i32,
            ..Self::default()
        }
    }

    /// Creates a new tracking camera to track a body with the given `tracking_id`.
    ///
    /// # Panics
    /// In debug builds, panics if `tracking_id` exceeds `i32::MAX`.
    pub fn new_tracking(tracking_id: usize) -> Self {
        debug_assert!(tracking_id <= i32::MAX as usize, "tracking_id exceeds i32::MAX");
        mjvCamera_ {
            type_: MjtCamera::mjCAMERA_TRACKING as i32,
            trackbodyid: tracking_id as i32,
            ..Self::default()
        }
    }

    /// Creates a new camera of user type.
    pub fn new_user() -> Self {
        mjvCamera_ {
            type_: MjtCamera::mjCAMERA_USER as i32,
            ..Self::default()
        }
    }

    /// Sets the camera into tracking mode.
    pub fn track(&mut self, tracking_id: usize) {
        self.type_ = MjtCamera::mjCAMERA_TRACKING as i32;
        self.fixedcamid = -1;
        self.trackbodyid = tracking_id as i32;
    }

    /// Sets the camera free from tracking.
    pub fn free(&mut self) {
        self.trackbodyid = -1;
        self.type_ = MjtCamera::mjCAMERA_FREE as i32;
    }

    /// Sets the camera to a fixed `camera_id`.
    pub fn fix(&mut self, camera_id: usize) {
        self.type_ = MjtCamera::mjCAMERA_FIXED as i32;
        self.fixedcamid = camera_id as i32;
        self.trackbodyid = -1;
    }

    /// Move camera with mouse.
    pub fn move_(&mut self, action: MjtMouse, model: &MjModel, dx: MjtNum, dy: MjtNum, scene: &MjvScene) {
        unsafe { mjv_moveCamera(model.ffi(), action as i32, dx, dy, scene.ffi(), self); };
    }

    /// Get the camera coordinate frame (pos, forward, up, right).
    ///
    /// # Panics
    /// Panics if this is a fixed camera (`MjtCamera::mjCAMERA_FIXED`) whose `fixedcamid` is out of range.
    pub fn frame<M: Deref<Target = MjModel>>(&self, data: &MjData<M>) -> ([MjtNum; 3], [MjtNum; 3], [MjtNum; 3], [MjtNum; 3]) {
        // Only the fixed-camera branch of mjv_cameraFrame dereferences the per-camera arrays; the
        // free/tracking branches derive the frame from azimuth/elevation and need no validation.
        if self.type_ == MjtCamera::mjCAMERA_FIXED as i32 {
            let ncam = data.model().ncam();
            assert!(
                self.fixedcamid >= 0 && (self.fixedcamid as i64) < ncam,
                "fixed camera id {} is out of range for a model with {} cameras",
                self.fixedcamid, ncam
            );
        }

        let mut headpos = [0.0; 3];
        let mut forward = [0.0; 3];
        let mut up = [0.0; 3];
        let mut right = [0.0; 3];
        unsafe {
            mjv_cameraFrame(
                &mut headpos, &mut forward, &mut up, &mut right,
                data.ffi(), self
            );
        }
        (headpos, forward, up, right)
    }

    /// Compute the `frustum` (zver, zhor, zclip) suitable for rendering.
    pub fn frustum(&self, model: &MjModel) -> ([f32; 2], [f32; 2], [f32; 2]) {
        let mut zver = [0.0; 2];
        let mut zhor = [0.0; 2];
        let mut zclip = [0.0; 2];
        unsafe {
            mjv_cameraFrustum(
                &mut zver, &mut zhor, &mut zclip,
                model.ffi(), self
            );
        }
        (zver, zhor, zclip)
    }
}

impl Default for MjvCamera {
    fn default() -> Self {
        // SAFETY: mjv_defaultCamera initializes all fields to valid defaults;
        // the MaybeUninit pointer is valid and aligned.
        unsafe {
            let mut c = MaybeUninit::uninit();
            mjv_defaultCamera(c.as_mut_ptr());
            c.assume_init()
        }
    }
}

/***********************************************************************************************************************
** mjvGLCamera
***********************************************************************************************************************/
/// OpenGL camera parameters (position, forward/up vectors, frustum planes).
pub type MjvGLCamera = mjvGLCamera;

impl MjvGLCamera {
    /// Average the current MjvGLCamera with the `other` MjvGLCamera.
    pub fn average_camera(&self, other: &Self) -> Self {
        unsafe { mjv_averageCamera (self, other) }
    }
}

/***********************************************************************************************************************
** MjvGeom
***********************************************************************************************************************/
/// Visual geometry element (type, size, material, RGBA, label, etc.) used in a scene.
pub type MjvGeom = mjvGeom;

impl MjvGeom {
    /// Sets the geom so that it acts as a connector (line, arrow, etc.) between
    /// two 3D points.
    ///
    /// This is a wrapper around MuJoCo's `mjv_connector`. The connector type
    /// is taken from the geom's current [`type_`](MjvGeom::type_) field, so
    /// set it to the desired connector type (e.g. `mjGEOM_LINE`, `mjGEOM_ARROW`)
    /// **before** calling this method, or initialize the geom
    /// with that type via [`MjvScene::create_geom`].
    pub fn connect(&mut self, width: MjtNum, from: [MjtNum; 3], to: [MjtNum; 3]) {
        unsafe {
            mjv_connector(self, self.type_, width, &from, &to);
        }
    }

    /// Compatibility method to convert the `label` attribute into a `String`.
    pub fn label(&self) -> String {
        let len = self.label.iter().position(|&c| c == 0).unwrap_or(self.label.len());
        // SAFETY: i8 and u8 have identical size (1) and alignment (1).
        let bytes: &[u8] = bytemuck::cast_slice(&self.label[..len]);
        String::from_utf8_lossy(bytes).to_string()
    }

    /// Writes `s` into the fixed-size label buffer, NUL-terminating it.
    /// # Errors
    /// Returns [`MjSceneError::NonAsciiLabel`] when `s` contains non-ASCII characters.
    /// Returns [`MjSceneError::LabelTooLong`] when `s` exceeds the buffer capacity
    /// (`self.label.len() - 1` bytes).
    pub fn set_label(&mut self, s: &str) -> Result<(), MjSceneError> {
        if !s.is_ascii() {
            return Err(MjSceneError::NonAsciiLabel);
        }
        let capacity = self.label.len() - 1;
        if s.len() > capacity {
            return Err(MjSceneError::LabelTooLong { len: s.len(), capacity });
        }
        let target: &mut [u8] = bytemuck::cast_slice_mut(&mut self.label[..s.len()]);
        target.copy_from_slice(s.as_bytes());
        self.label[s.len()] = 0;
        Ok(())
    }
}

/***********************************************************************************************************************
** MjvLight
***********************************************************************************************************************/
/// Visual light source parameters (position, direction, ambient/diffuse/specular RGB, etc.).
pub type MjvLight = mjvLight;

/***********************************************************************************************************************
** MjvOption
***********************************************************************************************************************/
/// Visualization rendering options (flags, label types, frame display, etc.).
pub type MjvOption = mjvOption;
impl Default for MjvOption {
    fn default() -> Self {
        let mut opt = MaybeUninit::uninit();
        // SAFETY: mjv_defaultOption initializes all fields to valid defaults;
        // the MaybeUninit pointer is valid and aligned.
        unsafe {
            mjv_defaultOption(opt.as_mut_ptr());
            opt.assume_init()
        }
    }
}

/***********************************************************************************************************************
** MjvFigure
***********************************************************************************************************************/
/// Abstraction for plotting figures.
pub type MjvFigure = mjvFigure;
impl Default for MjvFigure {
    fn default() -> Self {
        *Self::new_boxed()
    }
}

impl MjvFigure {
    /// Instantiates a new figure with default values, allocated on the heap.
    ///
    /// `MjvFigure` is ~800 KB; this constructor avoids placing it on the stack.
    pub fn new_boxed() -> Box<Self> {
        let mut opt = Box::new(MaybeUninit::uninit());
        // SAFETY: mjv_defaultFigure initializes all fields to valid defaults;
        // the MaybeUninit pointer is valid and aligned.
        unsafe {
            mjv_defaultFigure(opt.as_mut_ptr());
            opt.assume_init()
        }
    }

    /// Instantiates a new figure with default values, allocated on the heap.
    #[deprecated(since = "3.0.0", note = "use `new_boxed` instead")]
    pub fn new() -> Box<Self> {
        Self::new_boxed()
    }

    /// Draws the 2D figure to the `viewport` on screen.
    pub fn draw(&mut self, viewport: MjrRectangle, context: &MjrContext) {
        unsafe { mjr_figure(viewport, self, context.ffi()) };
    }
}

/// Figure options.
impl MjvFigure {
    getter_setter! {with, get, set, [
        flg_legend: bool; "whether to show legend.";
        flg_extend: bool; "whether to automatically extend axis ranges to fit data.";
        flg_barplot: bool; "whether to isolate line segments.";
        flg_selection: bool; "whether to show vertical selection line.";
        flg_symmetric: bool; "whether to make y-axis symmetric.";
    ]}

    // style settings
    getter_setter! {with, [
        gridsize: [i32; 2]; "number of grid points in (x, y).";
        gridrgb: [f32; 3]; "grid line RGB color.";
        figurergba: [f32; 4]; "figure RGBA color.";
        panergba: [f32; 4]; "pane RGBA color.";
        legendrgba: [f32; 4]; "legend RGBA color.";
        textrgb: [f32; 3]; "text RGB color.";
        linergb: [[f32; 3]; mjMAXLINE as usize]; "line colors.";
        range: [[f32; 2]; 2]; "axis ranges (min >= max means automatic).";
    ]}

    c_str_as_str_method! {with, get, set {
        xlabel; "the x-axis label.";
        title; "the title.";
        xformat; "the x-axis C's printf format (e.g., `%.1f`).";
        yformat; "the y-axis C's printf format (e.g., `%.1f`).";
        linename [plot_index: usize]; "the line name of plot with `plot_index`.";
    }}
}

/// Plot data manipulation
impl MjvFigure {

    /// Checks if the buffer is full for plot with `plot_index`.
    ///
    /// # Panics
    /// Panics if `plot_index >= mjMAXLINE`.
    ///
    /// Use [`MjvFigure::try_full`] for a fallible alternative.
    pub fn full(&self, plot_index: usize) -> bool {
        self.try_full(plot_index).unwrap()
    }

    /// Checks if the buffer is full for plot with `plot_index`.
    ///
    /// # Errors
    /// Returns [`MjSceneError::InvalidPlotIndex`] if `plot_index >= mjMAXLINE`.
    ///
    /// Use [`MjvFigure::full`] for a panicking alternative.
    pub fn try_full(&self, plot_index: usize) -> Result<bool, MjSceneError> {
        if plot_index >= mjMAXLINE as usize {
            return Err(MjSceneError::InvalidPlotIndex { plot_index, max_plots: mjMAXLINE as usize });
        }
        Ok(self.linepnt[plot_index] >= (self.linedata[plot_index].len() / 2) as i32)
    }

    /// Checks if the buffer is empty for plot with `plot_index`.
    ///
    /// # Panics
    /// Panics if `plot_index >= mjMAXLINE`.
    ///
    /// Use [`MjvFigure::try_empty`] for a fallible alternative.
    pub fn empty(&self, plot_index: usize) -> bool {
        self.try_empty(plot_index).unwrap()
    }

    /// Checks if the buffer is empty for plot with `plot_index`.
    ///
    /// # Errors
    /// Returns [`MjSceneError::InvalidPlotIndex`] if `plot_index >= mjMAXLINE`.
    ///
    /// Use [`MjvFigure::empty`] for a panicking alternative.
    pub fn try_empty(&self, plot_index: usize) -> Result<bool, MjSceneError> {
        if plot_index >= mjMAXLINE as usize {
            return Err(MjSceneError::InvalidPlotIndex { plot_index, max_plots: mjMAXLINE as usize });
        }
        Ok(self.linepnt[plot_index] == 0)
    }

    /// Pushes a new data point to buffer for the specific plot with `plot_index`.
    ///
    /// # Errors
    /// Returns [`MjSceneError::InvalidPlotIndex`] if `plot_index >= mjMAXLINE`.
    /// Returns [`MjSceneError::FigureBufferFull`] if the buffer for
    /// `plot_index` is already at capacity.
    pub fn push(&mut self, plot_index: usize, x: f32, y: f32) -> Result<(), MjSceneError> {
        if plot_index >= mjMAXLINE as usize {
            return Err(MjSceneError::InvalidPlotIndex { plot_index, max_plots: mjMAXLINE as usize });
        }
        let plot = &mut self.linedata[plot_index];
        let capacity = plot.len() / 2;
        let point_index = self.linepnt[plot_index] as usize;
        if point_index >= capacity {
            return Err(MjSceneError::FigureBufferFull { plot_index, capacity });
        }
        plot[2 * point_index] = x;
        plot[2 * point_index + 1] = y;
        self.linepnt[plot_index] += 1;
        Ok(())
    }

    /// Overrides existing data with a new data point at a specific `point_index` for specific plot with `plot_index`.
    ///
    /// # Errors
    /// Returns [`MjSceneError::InvalidPlotIndex`] if `plot_index >= mjMAXLINE`.
    /// Returns [`MjSceneError::FigureIndexOutOfBounds`] if `point_index` is
    /// not within the current data range for the given plot.
    pub fn set_at(
        &mut self,
        plot_index: usize,
        point_index: usize,
        x: f32,
        y: f32,
    ) -> Result<(), MjSceneError> {
        if plot_index >= mjMAXLINE as usize {
            return Err(MjSceneError::InvalidPlotIndex { plot_index, max_plots: mjMAXLINE as usize });
        }
        let current_len = self.linepnt[plot_index] as usize;
        if point_index >= current_len {
            return Err(MjSceneError::FigureIndexOutOfBounds {
                plot_index,
                point_index,
                current_len,
            });
        }
        let plot = &mut self.linedata[plot_index];
        plot[2 * point_index] = x;
        plot[2 * point_index + 1] = y;
        Ok(())
    }

    /// Clears the plot with `maybe_plot_index`.
    /// If `maybe_plot_index` is [`None`], all plots will be cleared.
    ///
    /// # Panics
    /// Panics if `maybe_plot_index` is `Some(i)` and `i >= mjMAXLINE`.
    pub fn clear(&mut self, maybe_plot_index: Option<usize>) {
        if let Some(plot_index) = maybe_plot_index {
            self.linepnt[plot_index] = 0;
        } else {
            self.linepnt.fill(0);
        }
    }

    /// Pops the first element from the plot data of plot with `plot_index`.
    ///
    /// # Returns
    /// Returns `Some((x, y))` when the plot contains any elements, otherwise `None` is returned.
    ///
    /// # Panics
    /// Panics if `plot_index >= mjMAXLINE`.
    ///
    /// Use [`MjvFigure::try_pop_front`] for a fallible alternative.
    pub fn pop_front(&mut self, plot_index: usize) -> Option<(f32, f32)> {
        self.try_pop_front(plot_index).unwrap()
    }

    /// Pops the first element from the plot data of plot with `plot_index`.
    ///
    /// # Errors
    /// Returns [`MjSceneError::InvalidPlotIndex`] if `plot_index >= mjMAXLINE`.
    ///
    /// Returns `Ok(Some((x, y)))` when the plot contains elements, `Ok(None)` when empty.
    ///
    /// Use [`MjvFigure::pop_front`] for a panicking alternative.
    pub fn try_pop_front(&mut self, plot_index: usize) -> Result<Option<(f32, f32)>, MjSceneError> {
        if plot_index >= mjMAXLINE as usize {
            return Err(MjSceneError::InvalidPlotIndex { plot_index, max_plots: mjMAXLINE as usize });
        }
        let len = self.linepnt[plot_index];
        if len <= 0 {
            return Ok(None);
        }
        let plot_data = &mut self.linedata[plot_index];
        let first = (plot_data[0], plot_data[1]);
        plot_data.copy_within(2..len as usize * 2, 0);
        self.linepnt[plot_index] -= 1;
        Ok(Some(first))
    }

    /// Pops the last element from the plot data of plot with `plot_index`.
    ///
    /// # Returns
    /// Returns `Some((x, y))` when the plot contains any elements, otherwise `None` is returned.
    ///
    /// # Panics
    /// Panics if `plot_index >= mjMAXLINE`.
    ///
    /// Use [`MjvFigure::try_pop_back`] for a fallible alternative.
    pub fn pop_back(&mut self, plot_index: usize) -> Option<(f32, f32)> {
        self.try_pop_back(plot_index).unwrap()
    }

    /// Pops the last element from the plot data of plot with `plot_index`.
    ///
    /// # Errors
    /// Returns [`MjSceneError::InvalidPlotIndex`] if `plot_index >= mjMAXLINE`.
    ///
    /// Returns `Ok(Some((x, y)))` when the plot contains elements, `Ok(None)` when empty.
    ///
    /// Use [`MjvFigure::pop_back`] for a panicking alternative.
    pub fn try_pop_back(&mut self, plot_index: usize) -> Result<Option<(f32, f32)>, MjSceneError> {
        if plot_index >= mjMAXLINE as usize {
            return Err(MjSceneError::InvalidPlotIndex { plot_index, max_plots: mjMAXLINE as usize });
        }
        let old_len = self.linepnt[plot_index];
        if old_len <= 0 {
            return Ok(None);
        }
        let plot_data = &mut self.linedata[plot_index];
        let new_start = ((old_len - 1) * 2) as usize;
        self.linepnt[plot_index] -= 1;
        Ok(Some((plot_data[new_start], plot_data[new_start + 1])))
    }

    /// Cuts the first `n` elements from the plot data of plot with `plot_index`.
    ///
    /// If `n` exceeds the current length, this is a no-op.
    ///
    /// # Errors
    /// Returns [`MjSceneError::InvalidPlotIndex`] if `plot_index >= mjMAXLINE`.
    pub fn cut_front(&mut self, plot_index: usize, n: usize) -> Result<(), MjSceneError> {
        if plot_index >= mjMAXLINE as usize {
            return Err(MjSceneError::InvalidPlotIndex { plot_index, max_plots: mjMAXLINE as usize });
        }
        let len = self.linepnt[plot_index];
        if len < 0 || (len as usize) < n {
            return Ok(());
        }

        self.linedata[plot_index].copy_within(2 * n..(len as usize * 2), 0);
        self.linepnt[plot_index] -= n as i32;
        Ok(())
    }

    /// Cuts the last `n` elements from the plot data of plot with `plot_index`.
    ///
    /// If `n` exceeds the current length, this is a no-op.
    ///
    /// # Errors
    /// Returns [`MjSceneError::InvalidPlotIndex`] if `plot_index >= mjMAXLINE`.
    pub fn cut_end(&mut self, plot_index: usize, n: usize) -> Result<(), MjSceneError> {
        if plot_index >= mjMAXLINE as usize {
            return Err(MjSceneError::InvalidPlotIndex { plot_index, max_plots: mjMAXLINE as usize });
        }
        let len = self.linepnt[plot_index];
        if len < 0 || (len as usize) < n {
            return Ok(());
        }
        self.linepnt[plot_index] -= n as i32;
        Ok(())
    }
}


/***********************************************************************************************************************
** MjvScene
***********************************************************************************************************************/
/// 3D scene visualization.
/// This struct provides a way to render visual-only geometry.
///
/// The scene does not hold a reference to the model; the caller is responsible for
/// ensuring that the same model (identified by signature) is used consistently.
/// Passing data from a different model to [`MjvScene::update`] or
/// [`MjvScene::find_selection`] will panic.
#[derive(Debug)]
pub struct MjvScene {
    ffi: Box<mjvScene>,
    signature: u64,
    /// Cached from the model at construction time for the flex/skin array slice accessors.
    nflexedge: MjtSize,
    nflexvert: MjtSize,
    nskinvert: MjtSize,
}

impl MjvScene {
    /// Creates a new scene for `model`, allocating space for up to `max_geom` geoms.
    ///
    /// # Panics
    /// In debug builds, panics if `max_geom` exceeds `i32::MAX`.
    pub fn new<M: Deref<Target = MjModel>>(model: M, max_geom: usize) -> Self {
        debug_assert!(max_geom <= i32::MAX as usize, "max_geom exceeds i32::MAX");
        let model_ffi = model.ffi();
        let nflexedge = model_ffi.nflexedge;
        let nflexvert = model_ffi.nflexvert;
        let nskinvert = model_ffi.nskinvert;
        let signature = model.signature();
        // SAFETY: mjv_defaultScene + mjv_makeScene initialize the struct and allocate
        // internal geom buffers; model pointer is valid for the duration of this call.
        let scn = unsafe {
            let mut t = Box::new_uninit();
            mjv_defaultScene(t.as_mut_ptr());
            mjv_makeScene(model_ffi, t.as_mut_ptr(), max_geom as i32);
            t.assume_init()
        };

        Self { ffi: scn, signature, nflexedge, nflexvert, nskinvert }
    }

    /// Returns the model signature this scene was created for.
    pub fn signature(&self) -> u64 {
        self.signature
    }

    /// Panics if `data_sig` does not match this scene's model signature.
    fn assert_signature(&self, data_sig: u64) {
        assert_eq!(
            self.signature, data_sig,
            "model signature mismatch: scene {:#X}, data model {:#X}",
            self.signature, data_sig
        );
    }

    /// Updates the scene from the current simulation state in `data`.
    ///
    /// The `catmask` parameter controls which geom categories are included
    /// (e.g., [`MjtCatBit::mjCAT_ALL`] for everything, or a bitwise OR of
    /// [`MjtCatBit::mjCAT_STATIC`], [`MjtCatBit::mjCAT_DYNAMIC`], [`MjtCatBit::mjCAT_DECOR`]).
    ///
    /// # Panics
    /// - Panics if `data` was created from a different model than this scene.
    /// - Panics if `cam` is a fixed camera ([`MjtCamera::mjCAMERA_FIXED`]) whose `fixedcamid` is
    ///   out of range for the model in `data`.
    /// - Panics if `perturb.select` is out of range (greater than or equal to the number of
    ///   bodies) for the model in `data`.
    pub fn update_with_catmask<M: Deref<Target = MjModel>>(
        &mut self, data: &mut MjData<M>, opt: &MjvOption, perturb: &MjvPerturb,
        cam: &mut MjvCamera, catmask: i32,
    ) {
        self.assert_signature(data.model().signature());
        // mjv_updateScene -> mjv_updateCamera calls mjv_cameraFrame, whose mjCAMERA_FIXED branch
        // reads d->cam_xmat + 9*fixedcamid / d->cam_xpos + 3*fixedcamid *before* C performs its own
        // range check, so an out-of-range id is an out-of-bounds read. Guard it here, matching the
        // check already in MjvCamera::frame(). (The free/tracking branches derive the frame from
        // azimuth/elevation, and the tracking body id is range-checked by C before use.)
        if cam.type_ == MjtCamera::mjCAMERA_FIXED as i32 {
            let ncam = data.model().ncam();
            assert!(
                cam.fixedcamid >= 0 && (cam.fixedcamid as i64) < ncam,
                "fixed camera id {} is out of range for a model with {} cameras",
                cam.fixedcamid, ncam
            );
        }

        // MuJoCo does no bound checking for pert->select, thus invalid IDs leads to out-of-bound reads.
        assert!((perturb.select as MjtSize) < data.model().nbody(), "selected perturbated body ID is outside the valid range");

        unsafe {
            mjv_updateScene(
                data.model().ffi(), data.ffi_mut(), opt, perturb,
                cam, catmask, self.ffi.as_mut()
            );
        }
    }

    /// Updates the scene from the current simulation state in `data`, including all geom categories.
    ///
    /// This is equivalent to calling [`update_with_catmask`](Self::update_with_catmask) with
    /// [`MjtCatBit::mjCAT_ALL`].
    ///
    /// # Panics
    /// Panics under the same conditions as [`update_with_catmask`](Self::update_with_catmask):
    /// a model-signature mismatch, an out-of-range fixed-camera id, or an out-of-range
    /// `perturb.select`.
    pub fn update<M: Deref<Target = MjModel>>(&mut self, data: &mut MjData<M>, opt: &MjvOption, perturb: &MjvPerturb, cam: &mut MjvCamera) {
        self.update_with_catmask(data, opt, perturb, cam, MjtCatBit::mjCAT_ALL as i32);
    }

    /// Creates a new [`MjvGeom`] in this scene, returning a mutable reference to it.
    /// The geom reference is valid for the duration of the `&mut self` borrow.
    ///
    /// # Panics
    /// Panics when `ngeom >= maxgeom` (the scene's geom buffer is full).
    ///
    /// Use [`MjvScene::try_create_geom`] for a fallible alternative.
    pub fn create_geom(
        &mut self, geom_type: MjtGeom, size: Option<[MjtNum; 3]>,
        pos: Option<[MjtNum; 3]>, mat: Option<[MjtNum; 9]>, rgba: Option<[f32; 4]>
    ) -> &mut MjvGeom {
        self.try_create_geom(geom_type, size, pos, mat, rgba).expect("create_geom failed: scene full")
    }

    /// Fallible version of [`MjvScene::create_geom`].
    /// # Errors
    /// Returns [`MjSceneError::SceneFull`] when `ngeom >= maxgeom`.
    pub fn try_create_geom(
        &mut self, geom_type: MjtGeom, size: Option<[MjtNum; 3]>,
        pos: Option<[MjtNum; 3]>, mat: Option<[MjtNum; 9]>, rgba: Option<[f32; 4]>
    ) -> Result<&mut MjvGeom, MjSceneError> {
        if self.ffi.ngeom >= self.ffi.maxgeom {
            return Err(MjSceneError::SceneFull { capacity: self.ffi.maxgeom });
        }

        let size_ptr = size.as_ref().map_or(ptr::null(), |x| x);
        let pos_ptr  = pos.as_ref().map_or(ptr::null(), |x| x);
        let mat_ptr  = mat.as_ref().map_or(ptr::null(), |x| x);
        let rgba_ptr = rgba.as_ref().map_or(ptr::null(), |x| x);

        // SAFETY: ngeom < maxgeom guarantees we are within the allocated buffer.
        unsafe {
            let p_geom = self.ffi.geoms.add(self.ffi.ngeom as usize);
            mjv_initGeom(p_geom, geom_type as i32, size_ptr, pos_ptr, mat_ptr, rgba_ptr);
            self.ffi.ngeom += 1;
            // Safety: p_geom is guaranteed non-null (allocated by mjv_makeScene).
            Ok(&mut *p_geom)
        }
    }

    /// Clears the created geoms.
    pub fn clear_geom(&mut self) {
        self.ffi.ngeom = 0;
    }

    /// Removes the last geom from the scene.
    /// Does nothing if the scene contains no geoms.
    pub fn pop_geom(&mut self) {
        if self.ffi.ngeom == 0 {
            return;
        }

        self.ffi.ngeom -= 1;
    }

    /// Renders the scene to the screen. This does not automatically make the OpenGL context current.
    pub fn render(&mut self, viewport: &MjrRectangle, context: &MjrContext){
        unsafe {
            mjr_render(*viewport, self.ffi_mut(), context.ffi());
        }
    }

    /// Returns the selection point based on a mouse click.
    /// This is a wrapper around `mjv_select()`.
    ///
    /// # Panics
    /// Panics if `data` was created from a different model than this scene.
    pub fn find_selection<M: Deref<Target = MjModel>>(
        &self, data: &mut MjData<M>, option: &MjvOption,
        aspect_ratio: MjtNum, relx: MjtNum, rely: MjtNum,
    ) -> SceneSelection {
        self.assert_signature(data.model().signature());
        let (mut geom_id, mut flex_id, mut skin_id) = (-1 , -1, -1);
        let mut selpnt = [0.0; 3];
        let body_id = unsafe {
            mjv_select(
                data.model().ffi(), data.ffi(), option,
                aspect_ratio, relx, rely, self.ffi(), &mut selpnt,
                &mut geom_id, &mut flex_id, &mut skin_id
            )
        };
        let to_opt = |v| if v >= 0 { Some(v as usize) } else { None };
        SceneSelection { body_id: to_opt(body_id), geom_id: to_opt(geom_id), flex_id: to_opt(flex_id), skin_id: to_opt(skin_id), point: selpnt }
    }

    /// Reference to the wrapped FFI struct.
    pub fn ffi(&self) -> &mjvScene {
        &self.ffi
    }

    /// Mutable reference to the wrapped FFI struct.
    ///
    /// # Safety
    /// Modifying the underlying FFI struct directly can break the invariants
    /// upheld by the `mujoco-rs` wrappers and cause undefined behavior.
    pub unsafe fn ffi_mut(&mut self) -> &mut mjvScene {
        &mut self.ffi
    }
}

/// Array slices.
impl MjvScene {
    // Scalar length arrays
    array_slice_dyn! {
        (mut = unsafe) flexedge: &[[i32; 2] [force]; "flex edge data"; nflexedge],
        flexvert: &[[f32; 3] [force]; "flex vertices"; nflexvert],
        skinvert: &[[f32; 3] [force]; "skin vertex data"; nskinvert],
        skinnormal: &[[f32; 3] [force]; "skin normal data"; nskinvert],
        (mut = unsafe) geoms: &[MjvGeom; "buffer for geoms"; ffi.ngeom],
        geomorder: &[i32; "buffer for ordering geoms by distance to camera"; ffi.ngeom],
        (mut = unsafe) flexedgeadr: &[i32; "address of flex edges"; ffi.nflex],
        (mut = unsafe) flexedgenum: &[i32; "number of edges in flex"; ffi.nflex],
        (mut = unsafe) flexvertadr: &[i32; "address of flex vertices"; ffi.nflex],
        (mut = unsafe) flexvertnum: &[i32; "number of vertices in flex"; ffi.nflex],
        (mut = unsafe) flexfaceadr: &[i32; "address of flex faces"; ffi.nflex],
        (mut = unsafe) flexfacenum: &[i32; "number of flex faces allocated"; ffi.nflex],
        (mut = unsafe) flexfaceused: &[i32; "number of flex faces currently in use"; ffi.nflex],
        (mut = unsafe) skinfacenum: &[i32; "number of faces in skin"; ffi.nskin],
        (mut = unsafe) skinvertadr: &[i32; "address of skin vertices"; ffi.nskin],
        (mut = unsafe) skinvertnum: &[i32; "number of vertices in skin"; ffi.nskin],
        lights: as_ptr as_mut_ptr &[MjvLight; "buffer for lights"; ffi.nlight]
    }

    // Arrays whose size is obtained via sum:
    // (multiplier; length array; length array length)
    //   => length = multiplier * sum(length_array)
    array_slice_dyn! {
        summed {
            flexface: &[f32; "flex faces vertices"; [9; (ffi.flexfacenum); (ffi.nflex)]],
            flexnormal: &[f32; "flex face normals"; [9; (ffi.flexfacenum); (ffi.nflex)]],
            flextexcoord: &[f32; "flex face texture coordinates"; [6; (ffi.flexfacenum); (ffi.nflex)]]
        }
    }
}


/// Public API getters / setters / builders.
impl MjvScene {
    getter_setter! {get, [
        [ffi] maxgeom: i32; "size of allocated geom buffer.";
        [ffi] ngeom: i32; "number of geoms currently in buffer.";
        [ffi] nflex: i32; "number of flexes.";
        [ffi] nskin: i32; "number of skins.";
        [ffi] nlight: i32; "number of lights currently in buffer.";
        [ffi] status: i32; "status; 0: ok, 1: geoms exhausted.";
    ]}

    getter_setter! {get, [
        [ffi] flexvertopt: bool; "copy of mjVIS_FLEXVERT mjvOption flag.";
        [ffi] flexedgeopt: bool; "copy of mjVIS_FLEXEDGE mjvOption flag.";
        [ffi] flexfaceopt: bool; "copy of mjVIS_FLEXFACE mjvOption flag.";
        [ffi] flexskinopt: bool; "copy of mjVIS_FLEXSKIN mjvOption flag.";
    ]}

    getter_setter! {with, get, set, [
        [ffi, ffi_mut] stereo: MjtStereo [force]; "stereoscopic rendering.";
    ]}

    getter_setter! {with, get, set, [
        [ffi, ffi_mut] scale: f32; "model scaling.";
        [ffi, ffi_mut] framewidth: i32; "frame pixel width; 0: disable framing.";
    ]}

    getter_setter! {with, get, set, [
        [ffi, ffi_mut] enabletransform: bool; "enable model transformation.";
    ]}

    getter_setter! {with, get, [
        [ffi, ffi_mut] camera: &[MjvGLCamera; 2]; "left and right camera.";
        [ffi, ffi_mut] translate: &[f32; 3]; "model translation.";
        [ffi, ffi_mut] rotate: &[f32; 4]; "model quaternion rotation.";
        [ffi, ffi_mut] framergb: &[f32; 3]; "frame color.";
    ]}

    getter_setter! {get, [
        [ffi, ffi_mut] flags: &[MjtByte; MjtRndFlag::mjNRNDFLAG as usize]; "rendering flags (indexed by mjtRndFlag).";
    ]}
}


impl Drop for MjvScene {
    fn drop(&mut self) {
        // SAFETY: self.ffi is a valid initialized MjvScene; called exactly once in Drop.
        unsafe {
            mjv_freeScene(self.ffi.as_mut());
        }
    }
}

// SAFETY: MjvScene exclusively owns the heap allocation behind Box<mjvScene>.
// The raw pointers inside mjvScene (geoms, lights, etc.) point into memory owned
// by the same allocation, so no aliasing with other threads is possible. All
// mutation requires &mut self, so &MjvScene sharing across threads is safe.
unsafe impl Send for MjvScene {}
unsafe impl Sync for MjvScene {}

#[cfg(test)]
mod tests {
    use super::*;

    const EXAMPLE_MODEL: &str = "
    <mujoco>
    <worldbody>
        <light ambient=\"0.2 0.2 0.2\"/>
        <body name=\"ball\">
            <geom name=\"green_sphere\" pos=\".2 .2 .2\" size=\".1\" rgba=\"0 1 0 1\"/>
            <joint type=\"free\"/>
        </body>

        <geom name=\"floor\" type=\"plane\" size=\"10 10 1\" euler=\"5 0 0\"/>

    </worldbody>
    </mujoco>
    ";

    /* Tests setup */
    fn load_model() -> MjModel {
        MjModel::from_xml_string(EXAMPLE_MODEL).unwrap()
    }

    #[test]
    #[allow(non_snake_case)]
    fn test_MjvGeom() {
        let model = load_model();
        let mut scene = MjvScene::new(&model, 1000);
        
        /* Test label handling. Other things are trivial one-liners. */
        let geom = scene.create_geom(MjtGeom::mjGEOM_SPHERE, None, None, None, None);
        let label = "Hello World";
        geom.set_label(label).unwrap();
        assert_eq!(geom.label(), label);
    }

    /// A fixed camera whose id is out of range for the model must panic in `frame` instead of
    /// triggering an out-of-bounds read in MuJoCo's `mjv_cameraFrame` (which indexes
    /// `cam_xpos`/`cam_xmat` by `fixedcamid` without bounds checks).
    #[test]
    #[should_panic(expected = "out of range")]
    fn test_camera_frame_fixed_id_out_of_range_panics() {
        let model = load_model();          // EXAMPLE_MODEL defines no <camera>, so ncam == 0
        let data = model.make_data();
        let camera = MjvCamera::new_fixed(0);  // fixedcamid = 0, but ncam = 0 -> out of range
        let _ = camera.frame(&data);
    }

    /// `MjvScene::update` must apply the same fixed-camera range check as `frame`. Otherwise a fixed
    /// camera with an out-of-range id reaches MuJoCo's `mjv_cameraFrame` (which reads
    /// `cam_xmat`/`cam_xpos` indexed by `fixedcamid`) *before* C runs its own range check.
    #[test]
    #[should_panic(expected = "out of range")]
    fn test_scene_update_fixed_camera_out_of_range_panics() {
        let model = load_model();          // no <camera>, so ncam == 0
        let mut scene = MjvScene::new(&model, 1000);
        let mut data = model.make_data();
        let (opt, pert) = (MjvOption::default(), MjvPerturb::default());
        let mut camera = MjvCamera::new_fixed(9999);
        scene.update(&mut data, &opt, &pert, &mut camera);
    }

    /// A perturbation whose `select` is out of range for the model must panic in `move_` instead of
    /// triggering an out-of-bounds read in MuJoCo's `mjv_movePerturb`, which dereferences
    /// `d->xmat + 9*select` (move-relative) before any range check and has no `select <= 0`
    /// early-out (unlike the `mjv_updateScene` path).
    #[test]
    #[should_panic(expected = "out of range")]
    fn test_perturb_move_select_out_of_range_panics() {
        let model = load_model();          // nbody == 2 (world + "ball")
        let data = model.make_data();
        let scene = MjvScene::new(&model, 100);
        let mut pert = MjvPerturb { select: 1_000_000, ..Default::default() };  // far beyond nbody
        pert.move_(&data, MjtMouse::mjMOUSE_MOVE_H_REL, 0.1, 0.1, &scene);
    }

    #[test]
    fn test_scene_geom_pop() {
        const N_GEOM: usize = 10;
        const N_GEOM_POP: usize = 11;

        let model = load_model();
        let mut scene = MjvScene::new(&model, 1000);

        for _ in 0..N_GEOM {
            scene.create_geom(MjtGeom::mjGEOM_SPHERE, None, None, None, None);
        }

        assert_eq!(scene.geoms().len(), N_GEOM);

        for _ in 0..N_GEOM_POP {
            scene.pop_geom();
        }

        assert_eq!(scene.geoms().len(), 0);
    }

    #[test]
    fn test_scene_slices() {
        let model = load_model();
        let scene = MjvScene::new(&model, 100);

        assert_eq!(scene.lights().len(), scene.ffi().nlight as usize);
        assert_eq!(scene.geomorder().len(), scene.ffi().ngeom as usize);
        assert_eq!(scene.geoms().len(), scene.ffi().ngeom as usize);
    }

    #[test]
    fn test_figure() {
        let mut fig = MjvFigure::new_boxed();
        let plot = 0;

        // Initially empty
        assert!(fig.empty(plot));
        assert_eq!(fig.pop_front(plot), None);
        assert_eq!(fig.pop_back(plot), None);

        // Push two points
        fig.push(plot, 1.0, 2.0).unwrap();
        fig.push(plot, 3.0, 4.0).unwrap();

        assert!(!fig.empty(plot));

        // Pop from front (FIFO)
        let first = fig.pop_front(plot);
        assert_eq!(first, Some((1.0, 2.0)));

        // Pop from back (LIFO on remaining element)
        let last = fig.pop_back(plot);
        assert_eq!(last, Some((3.0, 4.0)));

        // Now empty again
        assert!(fig.empty(plot));
        assert_eq!(fig.pop_front(plot), None);
        assert_eq!(fig.pop_back(plot), None);
    }

    /// Tests `getter_setter!` bool roundtrip for `enabletransform` on MjvScene.
    #[test]
    fn test_bool_getter_setter_roundtrip() {
        let model = load_model();
        let mut scene = MjvScene::new(&model, 100);

        // Default should be false
        assert!(!scene.enabletransform());

        scene.set_enabletransform(true);
        assert!(scene.enabletransform());

        scene.set_enabletransform(false);
        assert!(!scene.enabletransform());
    }

    /// Tests `getter_setter! force!` enum roundtrip for stereo (MjtStereo) on MjvScene.
    #[test]
    fn test_force_enum_getter_setter_roundtrip() {
        let model = load_model();
        let mut scene = MjvScene::new(&model, 100);

        // Default stereo mode
        let original = scene.stereo();
        assert_eq!(original, MjtStereo::mjSTEREO_NONE);

        scene.set_stereo(MjtStereo::mjSTEREO_QUADBUFFERED);
        assert_eq!(scene.stereo(), MjtStereo::mjSTEREO_QUADBUFFERED);

        scene.set_stereo(MjtStereo::mjSTEREO_SIDEBYSIDE);
        assert_eq!(scene.stereo(), MjtStereo::mjSTEREO_SIDEBYSIDE);
    }

    /// Tests that `create_geom` returns `SceneFull` when the scene capacity is exhausted.
    #[test]
    fn test_scene_full_error() {
        let model = load_model();
        let mut scene = MjvScene::new(&model, 2);

        // Fill to capacity
        scene.create_geom(MjtGeom::mjGEOM_SPHERE, None, None, None, None);
        scene.create_geom(MjtGeom::mjGEOM_SPHERE, None, None, None, None);

        // Next should fail
        let err = scene.try_create_geom(MjtGeom::mjGEOM_SPHERE, None, None, None, None).unwrap_err();
        assert!(matches!(err, MjSceneError::SceneFull { capacity: 2 }));
    }

    /// Tests `set_label` boundary: too-long label returns `LabelTooLong`,
    /// max-length label succeeds with roundtrip.
    #[test]
    fn test_geom_label_boundary() {
        let model = load_model();
        let mut scene = MjvScene::new(&model, 10);
        let geom = scene.create_geom(MjtGeom::mjGEOM_BOX, None, None, None, None);

        // Determine capacity (buffer len - 1 for NUL)
        let capacity = geom.label.len() - 1;

        // Max-length label should succeed
        let max_label: String = "A".repeat(capacity);
        geom.set_label(&max_label).unwrap();
        assert_eq!(geom.label(), max_label);

        // One byte too long should fail
        let too_long: String = "B".repeat(capacity + 1);
        let err = geom.set_label(&too_long).unwrap_err();
        assert!(matches!(err, MjSceneError::LabelTooLong { .. }));

        // Empty label should work
        geom.set_label("").unwrap();
        assert_eq!(geom.label(), "");
    }

    /// Tests `push` returns `FigureBufferFull` at capacity,
    /// and push succeeds after `pop_back` frees a slot.
    #[test]
    fn test_figure_push_overflow() {
        let mut fig = MjvFigure::new_boxed();
        let plot = 0;
        let capacity = fig.linedata[plot].len() / 2;

        // Fill to capacity
        for i in 0..capacity {
            fig.push(plot, i as f32, i as f32).unwrap();
        }
        assert!(fig.full(plot));

        // Next push should fail
        let err = fig.push(plot, 0.0, 0.0).unwrap_err();
        assert!(matches!(err, MjSceneError::FigureBufferFull { plot_index: 0, .. }));

        // Pop one element, then push should succeed again
        fig.pop_back(plot);
        assert!(!fig.full(plot));
        fig.push(plot, 99.0, 99.0).unwrap();
        assert!(fig.full(plot));
    }

    /// Verifies the getter and setter generated by `c_str_as_str_method!`
    /// for the `title` field of `MjvFigure`.
    ///
    /// Note: the `with_*` builder takes `self` by value. Because `MjvFigure` is ~800 KB,
    /// `new()` returns `Box<Self>` and calling `with_title` would move the value onto the
    /// stack, causing a stack overflow in a test thread. The setter covers the same code
    /// path, so the builder is not exercised here.
    #[test]
    fn test_c_str_as_str_method_title_roundtrip() {
        let mut fig = MjvFigure::new_boxed();

        // Default title should be empty.
        assert_eq!(fig.title(), "");

        // Setter must store the value and getter must return it.
        fig.set_title("hello");
        assert_eq!(fig.title(), "hello");

        // Overwrite with a different value to confirm the field actually changed.
        fig.set_title("world");
        assert_eq!(fig.title(), "world");
    }

    /// Exercises the `summed { ... }` arm of `array_slice_dyn!` via
    /// `MjvScene::flexface`, `flexnormal`, and `flextexcoord`. A model with no
    /// flex bodies must produce empty slices for all three.
    #[test]
    fn test_array_slice_dyn_summed_flex_empty() {
        let model = load_model();
        let scene = MjvScene::new(&model, 1000);
        assert!(scene.flexface().is_empty(), "flexface must be empty with no flex bodies");
        assert!(scene.flexnormal().is_empty(), "flexnormal must be empty with no flex bodies");
        assert!(scene.flextexcoord().is_empty(), "flextexcoord must be empty with no flex bodies");
    }
}