1pub use crate::no_render::*;
4
5#[repr(C)]
6#[derive(Debug, Default, Copy, Clone)]
7pub struct _mjrRect {
8 pub left: ::std::os::raw::c_int,
9 pub bottom: ::std::os::raw::c_int,
10 pub width: ::std::os::raw::c_int,
11 pub height: ::std::os::raw::c_int,
12}
13#[test]
14fn bindgen_test_layout__mjrRect() {
15 assert_eq!(
16 ::std::mem::size_of::<_mjrRect>(),
17 16usize,
18 concat!("Size of: ", stringify!(_mjrRect))
19 );
20 assert_eq!(
21 ::std::mem::align_of::<_mjrRect>(),
22 4usize,
23 concat!("Alignment of ", stringify!(_mjrRect))
24 );
25 assert_eq!(
26 unsafe { &(*(::std::ptr::null::<_mjrRect>())).left as *const _ as usize },
27 0usize,
28 concat!(
29 "Offset of field: ",
30 stringify!(_mjrRect),
31 "::",
32 stringify!(left)
33 )
34 );
35 assert_eq!(
36 unsafe { &(*(::std::ptr::null::<_mjrRect>())).bottom as *const _ as usize },
37 4usize,
38 concat!(
39 "Offset of field: ",
40 stringify!(_mjrRect),
41 "::",
42 stringify!(bottom)
43 )
44 );
45 assert_eq!(
46 unsafe { &(*(::std::ptr::null::<_mjrRect>())).width as *const _ as usize },
47 8usize,
48 concat!(
49 "Offset of field: ",
50 stringify!(_mjrRect),
51 "::",
52 stringify!(width)
53 )
54 );
55 assert_eq!(
56 unsafe { &(*(::std::ptr::null::<_mjrRect>())).height as *const _ as usize },
57 12usize,
58 concat!(
59 "Offset of field: ",
60 stringify!(_mjrRect),
61 "::",
62 stringify!(height)
63 )
64 );
65}
66pub type mjrRect = _mjrRect;
67#[repr(C)]
68#[derive(Copy, Clone)]
69pub struct _mjrContext {
70 pub lineWidth: f32,
71 pub shadowClip: f32,
72 pub shadowScale: f32,
73 pub fogStart: f32,
74 pub fogEnd: f32,
75 pub fogRGBA: [f32; 4usize],
76 pub shadowSize: ::std::os::raw::c_int,
77 pub offWidth: ::std::os::raw::c_int,
78 pub offHeight: ::std::os::raw::c_int,
79 pub offSamples: ::std::os::raw::c_int,
80 pub fontScale: ::std::os::raw::c_int,
81 pub auxWidth: [::std::os::raw::c_int; 10usize],
82 pub auxHeight: [::std::os::raw::c_int; 10usize],
83 pub auxSamples: [::std::os::raw::c_int; 10usize],
84 pub offFBO: ::std::os::raw::c_uint,
85 pub offFBO_r: ::std::os::raw::c_uint,
86 pub offColor: ::std::os::raw::c_uint,
87 pub offColor_r: ::std::os::raw::c_uint,
88 pub offDepthStencil: ::std::os::raw::c_uint,
89 pub offDepthStencil_r: ::std::os::raw::c_uint,
90 pub shadowFBO: ::std::os::raw::c_uint,
91 pub shadowTex: ::std::os::raw::c_uint,
92 pub auxFBO: [::std::os::raw::c_uint; 10usize],
93 pub auxFBO_r: [::std::os::raw::c_uint; 10usize],
94 pub auxColor: [::std::os::raw::c_uint; 10usize],
95 pub auxColor_r: [::std::os::raw::c_uint; 10usize],
96 pub ntexture: ::std::os::raw::c_int,
97 pub textureType: [::std::os::raw::c_int; 100usize],
98 pub texture: [::std::os::raw::c_uint; 100usize],
99 pub basePlane: ::std::os::raw::c_uint,
100 pub baseMesh: ::std::os::raw::c_uint,
101 pub baseHField: ::std::os::raw::c_uint,
102 pub baseBuiltin: ::std::os::raw::c_uint,
103 pub baseFontNormal: ::std::os::raw::c_uint,
104 pub baseFontShadow: ::std::os::raw::c_uint,
105 pub baseFontBig: ::std::os::raw::c_uint,
106 pub rangePlane: ::std::os::raw::c_int,
107 pub rangeMesh: ::std::os::raw::c_int,
108 pub rangeHField: ::std::os::raw::c_int,
109 pub rangeBuiltin: ::std::os::raw::c_int,
110 pub rangeFont: ::std::os::raw::c_int,
111 pub nskin: ::std::os::raw::c_int,
112 pub skinvertVBO: *mut ::std::os::raw::c_uint,
113 pub skinnormalVBO: *mut ::std::os::raw::c_uint,
114 pub skintexcoordVBO: *mut ::std::os::raw::c_uint,
115 pub skinfaceVBO: *mut ::std::os::raw::c_uint,
116 pub charWidth: [::std::os::raw::c_int; 127usize],
117 pub charWidthBig: [::std::os::raw::c_int; 127usize],
118 pub charHeight: ::std::os::raw::c_int,
119 pub charHeightBig: ::std::os::raw::c_int,
120 pub glewInitialized: ::std::os::raw::c_int,
121 pub windowAvailable: ::std::os::raw::c_int,
122 pub windowSamples: ::std::os::raw::c_int,
123 pub windowStereo: ::std::os::raw::c_int,
124 pub windowDoublebuffer: ::std::os::raw::c_int,
125 pub currentBuffer: ::std::os::raw::c_int,
126}
127#[test]
128fn bindgen_test_layout__mjrContext() {
129 assert_eq!(
130 ::std::mem::size_of::<_mjrContext>(),
131 2304usize,
132 concat!("Size of: ", stringify!(_mjrContext))
133 );
134 assert_eq!(
135 ::std::mem::align_of::<_mjrContext>(),
136 8usize,
137 concat!("Alignment of ", stringify!(_mjrContext))
138 );
139 assert_eq!(
140 unsafe {
141 &(*(::std::ptr::null::<_mjrContext>())).lineWidth as *const _ as usize
142 },
143 0usize,
144 concat!(
145 "Offset of field: ",
146 stringify!(_mjrContext),
147 "::",
148 stringify!(lineWidth)
149 )
150 );
151 assert_eq!(
152 unsafe {
153 &(*(::std::ptr::null::<_mjrContext>())).shadowClip as *const _ as usize
154 },
155 4usize,
156 concat!(
157 "Offset of field: ",
158 stringify!(_mjrContext),
159 "::",
160 stringify!(shadowClip)
161 )
162 );
163 assert_eq!(
164 unsafe {
165 &(*(::std::ptr::null::<_mjrContext>())).shadowScale as *const _ as usize
166 },
167 8usize,
168 concat!(
169 "Offset of field: ",
170 stringify!(_mjrContext),
171 "::",
172 stringify!(shadowScale)
173 )
174 );
175 assert_eq!(
176 unsafe {
177 &(*(::std::ptr::null::<_mjrContext>())).fogStart as *const _ as usize
178 },
179 12usize,
180 concat!(
181 "Offset of field: ",
182 stringify!(_mjrContext),
183 "::",
184 stringify!(fogStart)
185 )
186 );
187 assert_eq!(
188 unsafe { &(*(::std::ptr::null::<_mjrContext>())).fogEnd as *const _ as usize },
189 16usize,
190 concat!(
191 "Offset of field: ",
192 stringify!(_mjrContext),
193 "::",
194 stringify!(fogEnd)
195 )
196 );
197 assert_eq!(
198 unsafe { &(*(::std::ptr::null::<_mjrContext>())).fogRGBA as *const _ as usize },
199 20usize,
200 concat!(
201 "Offset of field: ",
202 stringify!(_mjrContext),
203 "::",
204 stringify!(fogRGBA)
205 )
206 );
207 assert_eq!(
208 unsafe {
209 &(*(::std::ptr::null::<_mjrContext>())).shadowSize as *const _ as usize
210 },
211 36usize,
212 concat!(
213 "Offset of field: ",
214 stringify!(_mjrContext),
215 "::",
216 stringify!(shadowSize)
217 )
218 );
219 assert_eq!(
220 unsafe {
221 &(*(::std::ptr::null::<_mjrContext>())).offWidth as *const _ as usize
222 },
223 40usize,
224 concat!(
225 "Offset of field: ",
226 stringify!(_mjrContext),
227 "::",
228 stringify!(offWidth)
229 )
230 );
231 assert_eq!(
232 unsafe {
233 &(*(::std::ptr::null::<_mjrContext>())).offHeight as *const _ as usize
234 },
235 44usize,
236 concat!(
237 "Offset of field: ",
238 stringify!(_mjrContext),
239 "::",
240 stringify!(offHeight)
241 )
242 );
243 assert_eq!(
244 unsafe {
245 &(*(::std::ptr::null::<_mjrContext>())).offSamples as *const _ as usize
246 },
247 48usize,
248 concat!(
249 "Offset of field: ",
250 stringify!(_mjrContext),
251 "::",
252 stringify!(offSamples)
253 )
254 );
255 assert_eq!(
256 unsafe {
257 &(*(::std::ptr::null::<_mjrContext>())).fontScale as *const _ as usize
258 },
259 52usize,
260 concat!(
261 "Offset of field: ",
262 stringify!(_mjrContext),
263 "::",
264 stringify!(fontScale)
265 )
266 );
267 assert_eq!(
268 unsafe {
269 &(*(::std::ptr::null::<_mjrContext>())).auxWidth as *const _ as usize
270 },
271 56usize,
272 concat!(
273 "Offset of field: ",
274 stringify!(_mjrContext),
275 "::",
276 stringify!(auxWidth)
277 )
278 );
279 assert_eq!(
280 unsafe {
281 &(*(::std::ptr::null::<_mjrContext>())).auxHeight as *const _ as usize
282 },
283 96usize,
284 concat!(
285 "Offset of field: ",
286 stringify!(_mjrContext),
287 "::",
288 stringify!(auxHeight)
289 )
290 );
291 assert_eq!(
292 unsafe {
293 &(*(::std::ptr::null::<_mjrContext>())).auxSamples as *const _ as usize
294 },
295 136usize,
296 concat!(
297 "Offset of field: ",
298 stringify!(_mjrContext),
299 "::",
300 stringify!(auxSamples)
301 )
302 );
303 assert_eq!(
304 unsafe { &(*(::std::ptr::null::<_mjrContext>())).offFBO as *const _ as usize },
305 176usize,
306 concat!(
307 "Offset of field: ",
308 stringify!(_mjrContext),
309 "::",
310 stringify!(offFBO)
311 )
312 );
313 assert_eq!(
314 unsafe {
315 &(*(::std::ptr::null::<_mjrContext>())).offFBO_r as *const _ as usize
316 },
317 180usize,
318 concat!(
319 "Offset of field: ",
320 stringify!(_mjrContext),
321 "::",
322 stringify!(offFBO_r)
323 )
324 );
325 assert_eq!(
326 unsafe {
327 &(*(::std::ptr::null::<_mjrContext>())).offColor as *const _ as usize
328 },
329 184usize,
330 concat!(
331 "Offset of field: ",
332 stringify!(_mjrContext),
333 "::",
334 stringify!(offColor)
335 )
336 );
337 assert_eq!(
338 unsafe {
339 &(*(::std::ptr::null::<_mjrContext>())).offColor_r as *const _ as usize
340 },
341 188usize,
342 concat!(
343 "Offset of field: ",
344 stringify!(_mjrContext),
345 "::",
346 stringify!(offColor_r)
347 )
348 );
349 assert_eq!(
350 unsafe {
351 &(*(::std::ptr::null::<_mjrContext>())).offDepthStencil as *const _ as usize
352 },
353 192usize,
354 concat!(
355 "Offset of field: ",
356 stringify!(_mjrContext),
357 "::",
358 stringify!(offDepthStencil)
359 )
360 );
361 assert_eq!(
362 unsafe {
363 &(*(::std::ptr::null::<_mjrContext>())).offDepthStencil_r as *const _
364 as usize
365 },
366 196usize,
367 concat!(
368 "Offset of field: ",
369 stringify!(_mjrContext),
370 "::",
371 stringify!(offDepthStencil_r)
372 )
373 );
374 assert_eq!(
375 unsafe {
376 &(*(::std::ptr::null::<_mjrContext>())).shadowFBO as *const _ as usize
377 },
378 200usize,
379 concat!(
380 "Offset of field: ",
381 stringify!(_mjrContext),
382 "::",
383 stringify!(shadowFBO)
384 )
385 );
386 assert_eq!(
387 unsafe {
388 &(*(::std::ptr::null::<_mjrContext>())).shadowTex as *const _ as usize
389 },
390 204usize,
391 concat!(
392 "Offset of field: ",
393 stringify!(_mjrContext),
394 "::",
395 stringify!(shadowTex)
396 )
397 );
398 assert_eq!(
399 unsafe { &(*(::std::ptr::null::<_mjrContext>())).auxFBO as *const _ as usize },
400 208usize,
401 concat!(
402 "Offset of field: ",
403 stringify!(_mjrContext),
404 "::",
405 stringify!(auxFBO)
406 )
407 );
408 assert_eq!(
409 unsafe {
410 &(*(::std::ptr::null::<_mjrContext>())).auxFBO_r as *const _ as usize
411 },
412 248usize,
413 concat!(
414 "Offset of field: ",
415 stringify!(_mjrContext),
416 "::",
417 stringify!(auxFBO_r)
418 )
419 );
420 assert_eq!(
421 unsafe {
422 &(*(::std::ptr::null::<_mjrContext>())).auxColor as *const _ as usize
423 },
424 288usize,
425 concat!(
426 "Offset of field: ",
427 stringify!(_mjrContext),
428 "::",
429 stringify!(auxColor)
430 )
431 );
432 assert_eq!(
433 unsafe {
434 &(*(::std::ptr::null::<_mjrContext>())).auxColor_r as *const _ as usize
435 },
436 328usize,
437 concat!(
438 "Offset of field: ",
439 stringify!(_mjrContext),
440 "::",
441 stringify!(auxColor_r)
442 )
443 );
444 assert_eq!(
445 unsafe {
446 &(*(::std::ptr::null::<_mjrContext>())).ntexture as *const _ as usize
447 },
448 368usize,
449 concat!(
450 "Offset of field: ",
451 stringify!(_mjrContext),
452 "::",
453 stringify!(ntexture)
454 )
455 );
456 assert_eq!(
457 unsafe {
458 &(*(::std::ptr::null::<_mjrContext>())).textureType as *const _ as usize
459 },
460 372usize,
461 concat!(
462 "Offset of field: ",
463 stringify!(_mjrContext),
464 "::",
465 stringify!(textureType)
466 )
467 );
468 assert_eq!(
469 unsafe { &(*(::std::ptr::null::<_mjrContext>())).texture as *const _ as usize },
470 772usize,
471 concat!(
472 "Offset of field: ",
473 stringify!(_mjrContext),
474 "::",
475 stringify!(texture)
476 )
477 );
478 assert_eq!(
479 unsafe {
480 &(*(::std::ptr::null::<_mjrContext>())).basePlane as *const _ as usize
481 },
482 1172usize,
483 concat!(
484 "Offset of field: ",
485 stringify!(_mjrContext),
486 "::",
487 stringify!(basePlane)
488 )
489 );
490 assert_eq!(
491 unsafe {
492 &(*(::std::ptr::null::<_mjrContext>())).baseMesh as *const _ as usize
493 },
494 1176usize,
495 concat!(
496 "Offset of field: ",
497 stringify!(_mjrContext),
498 "::",
499 stringify!(baseMesh)
500 )
501 );
502 assert_eq!(
503 unsafe {
504 &(*(::std::ptr::null::<_mjrContext>())).baseHField as *const _ as usize
505 },
506 1180usize,
507 concat!(
508 "Offset of field: ",
509 stringify!(_mjrContext),
510 "::",
511 stringify!(baseHField)
512 )
513 );
514 assert_eq!(
515 unsafe {
516 &(*(::std::ptr::null::<_mjrContext>())).baseBuiltin as *const _ as usize
517 },
518 1184usize,
519 concat!(
520 "Offset of field: ",
521 stringify!(_mjrContext),
522 "::",
523 stringify!(baseBuiltin)
524 )
525 );
526 assert_eq!(
527 unsafe {
528 &(*(::std::ptr::null::<_mjrContext>())).baseFontNormal as *const _ as usize
529 },
530 1188usize,
531 concat!(
532 "Offset of field: ",
533 stringify!(_mjrContext),
534 "::",
535 stringify!(baseFontNormal)
536 )
537 );
538 assert_eq!(
539 unsafe {
540 &(*(::std::ptr::null::<_mjrContext>())).baseFontShadow as *const _ as usize
541 },
542 1192usize,
543 concat!(
544 "Offset of field: ",
545 stringify!(_mjrContext),
546 "::",
547 stringify!(baseFontShadow)
548 )
549 );
550 assert_eq!(
551 unsafe {
552 &(*(::std::ptr::null::<_mjrContext>())).baseFontBig as *const _ as usize
553 },
554 1196usize,
555 concat!(
556 "Offset of field: ",
557 stringify!(_mjrContext),
558 "::",
559 stringify!(baseFontBig)
560 )
561 );
562 assert_eq!(
563 unsafe {
564 &(*(::std::ptr::null::<_mjrContext>())).rangePlane as *const _ as usize
565 },
566 1200usize,
567 concat!(
568 "Offset of field: ",
569 stringify!(_mjrContext),
570 "::",
571 stringify!(rangePlane)
572 )
573 );
574 assert_eq!(
575 unsafe {
576 &(*(::std::ptr::null::<_mjrContext>())).rangeMesh as *const _ as usize
577 },
578 1204usize,
579 concat!(
580 "Offset of field: ",
581 stringify!(_mjrContext),
582 "::",
583 stringify!(rangeMesh)
584 )
585 );
586 assert_eq!(
587 unsafe {
588 &(*(::std::ptr::null::<_mjrContext>())).rangeHField as *const _ as usize
589 },
590 1208usize,
591 concat!(
592 "Offset of field: ",
593 stringify!(_mjrContext),
594 "::",
595 stringify!(rangeHField)
596 )
597 );
598 assert_eq!(
599 unsafe {
600 &(*(::std::ptr::null::<_mjrContext>())).rangeBuiltin as *const _ as usize
601 },
602 1212usize,
603 concat!(
604 "Offset of field: ",
605 stringify!(_mjrContext),
606 "::",
607 stringify!(rangeBuiltin)
608 )
609 );
610 assert_eq!(
611 unsafe {
612 &(*(::std::ptr::null::<_mjrContext>())).rangeFont as *const _ as usize
613 },
614 1216usize,
615 concat!(
616 "Offset of field: ",
617 stringify!(_mjrContext),
618 "::",
619 stringify!(rangeFont)
620 )
621 );
622 assert_eq!(
623 unsafe { &(*(::std::ptr::null::<_mjrContext>())).nskin as *const _ as usize },
624 1220usize,
625 concat!(
626 "Offset of field: ",
627 stringify!(_mjrContext),
628 "::",
629 stringify!(nskin)
630 )
631 );
632 assert_eq!(
633 unsafe {
634 &(*(::std::ptr::null::<_mjrContext>())).skinvertVBO as *const _ as usize
635 },
636 1224usize,
637 concat!(
638 "Offset of field: ",
639 stringify!(_mjrContext),
640 "::",
641 stringify!(skinvertVBO)
642 )
643 );
644 assert_eq!(
645 unsafe {
646 &(*(::std::ptr::null::<_mjrContext>())).skinnormalVBO as *const _ as usize
647 },
648 1232usize,
649 concat!(
650 "Offset of field: ",
651 stringify!(_mjrContext),
652 "::",
653 stringify!(skinnormalVBO)
654 )
655 );
656 assert_eq!(
657 unsafe {
658 &(*(::std::ptr::null::<_mjrContext>())).skintexcoordVBO as *const _ as usize
659 },
660 1240usize,
661 concat!(
662 "Offset of field: ",
663 stringify!(_mjrContext),
664 "::",
665 stringify!(skintexcoordVBO)
666 )
667 );
668 assert_eq!(
669 unsafe {
670 &(*(::std::ptr::null::<_mjrContext>())).skinfaceVBO as *const _ as usize
671 },
672 1248usize,
673 concat!(
674 "Offset of field: ",
675 stringify!(_mjrContext),
676 "::",
677 stringify!(skinfaceVBO)
678 )
679 );
680 assert_eq!(
681 unsafe {
682 &(*(::std::ptr::null::<_mjrContext>())).charWidth as *const _ as usize
683 },
684 1256usize,
685 concat!(
686 "Offset of field: ",
687 stringify!(_mjrContext),
688 "::",
689 stringify!(charWidth)
690 )
691 );
692 assert_eq!(
693 unsafe {
694 &(*(::std::ptr::null::<_mjrContext>())).charWidthBig as *const _ as usize
695 },
696 1764usize,
697 concat!(
698 "Offset of field: ",
699 stringify!(_mjrContext),
700 "::",
701 stringify!(charWidthBig)
702 )
703 );
704 assert_eq!(
705 unsafe {
706 &(*(::std::ptr::null::<_mjrContext>())).charHeight as *const _ as usize
707 },
708 2272usize,
709 concat!(
710 "Offset of field: ",
711 stringify!(_mjrContext),
712 "::",
713 stringify!(charHeight)
714 )
715 );
716 assert_eq!(
717 unsafe {
718 &(*(::std::ptr::null::<_mjrContext>())).charHeightBig as *const _ as usize
719 },
720 2276usize,
721 concat!(
722 "Offset of field: ",
723 stringify!(_mjrContext),
724 "::",
725 stringify!(charHeightBig)
726 )
727 );
728 assert_eq!(
729 unsafe {
730 &(*(::std::ptr::null::<_mjrContext>())).glewInitialized as *const _ as usize
731 },
732 2280usize,
733 concat!(
734 "Offset of field: ",
735 stringify!(_mjrContext),
736 "::",
737 stringify!(glewInitialized)
738 )
739 );
740 assert_eq!(
741 unsafe {
742 &(*(::std::ptr::null::<_mjrContext>())).windowAvailable as *const _ as usize
743 },
744 2284usize,
745 concat!(
746 "Offset of field: ",
747 stringify!(_mjrContext),
748 "::",
749 stringify!(windowAvailable)
750 )
751 );
752 assert_eq!(
753 unsafe {
754 &(*(::std::ptr::null::<_mjrContext>())).windowSamples as *const _ as usize
755 },
756 2288usize,
757 concat!(
758 "Offset of field: ",
759 stringify!(_mjrContext),
760 "::",
761 stringify!(windowSamples)
762 )
763 );
764 assert_eq!(
765 unsafe {
766 &(*(::std::ptr::null::<_mjrContext>())).windowStereo as *const _ as usize
767 },
768 2292usize,
769 concat!(
770 "Offset of field: ",
771 stringify!(_mjrContext),
772 "::",
773 stringify!(windowStereo)
774 )
775 );
776 assert_eq!(
777 unsafe {
778 &(*(::std::ptr::null::<_mjrContext>())).windowDoublebuffer as *const _
779 as usize
780 },
781 2296usize,
782 concat!(
783 "Offset of field: ",
784 stringify!(_mjrContext),
785 "::",
786 stringify!(windowDoublebuffer)
787 )
788 );
789 assert_eq!(
790 unsafe {
791 &(*(::std::ptr::null::<_mjrContext>())).currentBuffer as *const _ as usize
792 },
793 2300usize,
794 concat!(
795 "Offset of field: ",
796 stringify!(_mjrContext),
797 "::",
798 stringify!(currentBuffer)
799 )
800 );
801}
802impl Default for _mjrContext {
803 fn default() -> Self {
804 unsafe { ::std::mem::zeroed() }
805 }
806}
807pub type mjrContext = _mjrContext;
808extern "C" {
809 pub fn mjr_defaultContext(con: *mut mjrContext);
810}
811extern "C" {
812 pub fn mjr_makeContext(
813 m: *const mjModel,
814 con: *mut mjrContext,
815 fontscale: ::std::os::raw::c_int,
816 );
817}
818extern "C" {
819 pub fn mjr_changeFont(fontscale: ::std::os::raw::c_int, con: *mut mjrContext);
820}
821extern "C" {
822 pub fn mjr_addAux(
823 index: ::std::os::raw::c_int,
824 width: ::std::os::raw::c_int,
825 height: ::std::os::raw::c_int,
826 samples: ::std::os::raw::c_int,
827 con: *mut mjrContext,
828 );
829}
830extern "C" {
831 pub fn mjr_freeContext(con: *mut mjrContext);
832}
833extern "C" {
834 pub fn mjr_uploadTexture(
835 m: *const mjModel,
836 con: *const mjrContext,
837 texid: ::std::os::raw::c_int,
838 );
839}
840extern "C" {
841 pub fn mjr_uploadMesh(
842 m: *const mjModel,
843 con: *const mjrContext,
844 meshid: ::std::os::raw::c_int,
845 );
846}
847extern "C" {
848 pub fn mjr_uploadHField(
849 m: *const mjModel,
850 con: *const mjrContext,
851 hfieldid: ::std::os::raw::c_int,
852 );
853}
854extern "C" {
855 pub fn mjr_restoreBuffer(con: *const mjrContext);
856}
857extern "C" {
858 pub fn mjr_setBuffer(framebuffer: ::std::os::raw::c_int, con: *mut mjrContext);
859}
860extern "C" {
861 pub fn mjr_readPixels(
862 rgb: *mut ::std::os::raw::c_uchar,
863 depth: *mut f32,
864 viewport: mjrRect,
865 con: *const mjrContext,
866 );
867}
868extern "C" {
869 pub fn mjr_drawPixels(
870 rgb: *const ::std::os::raw::c_uchar,
871 depth: *const f32,
872 viewport: mjrRect,
873 con: *const mjrContext,
874 );
875}
876extern "C" {
877 pub fn mjr_blitBuffer(
878 src: mjrRect,
879 dst: mjrRect,
880 flg_color: ::std::os::raw::c_int,
881 flg_depth: ::std::os::raw::c_int,
882 con: *const mjrContext,
883 );
884}
885extern "C" {
886 pub fn mjr_setAux(index: ::std::os::raw::c_int, con: *const mjrContext);
887}
888extern "C" {
889 pub fn mjr_blitAux(
890 index: ::std::os::raw::c_int,
891 src: mjrRect,
892 left: ::std::os::raw::c_int,
893 bottom: ::std::os::raw::c_int,
894 con: *const mjrContext,
895 );
896}
897extern "C" {
898 pub fn mjr_text(
899 font: ::std::os::raw::c_int,
900 txt: *const ::std::os::raw::c_char,
901 con: *const mjrContext,
902 x: f32,
903 y: f32,
904 r: f32,
905 g: f32,
906 b: f32,
907 );
908}
909extern "C" {
910 pub fn mjr_overlay(
911 font: ::std::os::raw::c_int,
912 gridpos: ::std::os::raw::c_int,
913 viewport: mjrRect,
914 overlay: *const ::std::os::raw::c_char,
915 overlay2: *const ::std::os::raw::c_char,
916 con: *const mjrContext,
917 );
918}
919extern "C" {
920 pub fn mjr_maxViewport(con: *const mjrContext) -> mjrRect;
921}
922extern "C" {
923 pub fn mjr_rectangle(viewport: mjrRect, r: f32, g: f32, b: f32, a: f32);
924}
925extern "C" {
926 pub fn mjr_figure(viewport: mjrRect, fig: *mut mjvFigure, con: *const mjrContext);
927}
928extern "C" {
929 pub fn mjr_render(viewport: mjrRect, scn: *mut mjvScene, con: *const mjrContext);
930}
931extern "C" {
932 pub fn mjr_finish();
933}
934extern "C" {
935 pub fn mjr_getError() -> ::std::os::raw::c_int;
936}
937extern "C" {
938 pub fn mjr_findRect(
939 x: ::std::os::raw::c_int,
940 y: ::std::os::raw::c_int,
941 nrect: ::std::os::raw::c_int,
942 rect: *const mjrRect,
943 ) -> ::std::os::raw::c_int;
944}