File size: 203,383 Bytes
2c55b92 | 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 1274 1275 1276 1277 1278 1279 1280 1281 1282 1283 1284 1285 1286 1287 1288 1289 1290 1291 1292 1293 1294 1295 1296 1297 1298 1299 1300 1301 1302 1303 1304 1305 1306 1307 1308 1309 1310 1311 1312 1313 1314 1315 1316 1317 1318 1319 1320 1321 1322 1323 1324 1325 1326 1327 1328 1329 1330 1331 1332 1333 1334 1335 1336 1337 1338 1339 1340 1341 1342 1343 1344 1345 1346 1347 1348 1349 1350 1351 1352 1353 1354 1355 1356 1357 1358 1359 1360 1361 1362 1363 1364 1365 1366 1367 1368 1369 1370 1371 1372 1373 1374 1375 1376 1377 1378 1379 1380 1381 1382 1383 1384 1385 1386 1387 1388 1389 1390 1391 1392 1393 1394 1395 1396 1397 1398 1399 1400 1401 1402 1403 1404 1405 1406 1407 1408 1409 1410 1411 1412 1413 1414 1415 1416 1417 1418 1419 1420 1421 1422 1423 1424 1425 1426 1427 1428 1429 1430 1431 1432 1433 1434 1435 1436 1437 1438 1439 1440 1441 1442 1443 1444 1445 1446 1447 1448 1449 1450 1451 1452 1453 1454 1455 1456 1457 1458 1459 1460 1461 1462 1463 1464 1465 1466 1467 1468 1469 1470 1471 1472 1473 1474 1475 1476 1477 1478 1479 1480 1481 1482 1483 1484 1485 1486 1487 1488 1489 1490 1491 1492 1493 1494 1495 1496 1497 1498 1499 1500 1501 1502 1503 1504 1505 1506 1507 1508 1509 1510 1511 1512 1513 1514 1515 1516 1517 1518 1519 1520 1521 1522 1523 1524 1525 1526 1527 1528 1529 1530 1531 1532 1533 1534 1535 1536 1537 1538 1539 1540 1541 1542 1543 1544 1545 1546 1547 1548 1549 1550 1551 1552 1553 1554 1555 1556 1557 1558 1559 1560 1561 1562 1563 1564 1565 1566 1567 1568 1569 1570 1571 1572 1573 1574 1575 1576 1577 1578 1579 1580 1581 1582 1583 1584 1585 1586 1587 1588 1589 1590 1591 1592 1593 1594 1595 1596 1597 1598 1599 1600 1601 1602 1603 1604 1605 1606 1607 1608 1609 1610 1611 1612 1613 1614 1615 1616 1617 1618 1619 1620 1621 1622 1623 1624 1625 1626 1627 1628 1629 1630 1631 1632 1633 1634 1635 1636 1637 1638 1639 1640 1641 1642 1643 1644 1645 1646 1647 1648 1649 1650 1651 1652 1653 1654 1655 1656 1657 1658 1659 1660 1661 1662 1663 1664 1665 1666 1667 1668 1669 1670 1671 1672 1673 1674 1675 1676 1677 1678 1679 1680 1681 1682 1683 1684 1685 1686 1687 1688 1689 1690 1691 1692 1693 1694 1695 1696 1697 1698 1699 1700 1701 1702 1703 1704 1705 1706 1707 1708 1709 1710 1711 1712 1713 1714 1715 1716 1717 1718 1719 1720 1721 1722 1723 1724 1725 1726 1727 1728 1729 1730 1731 1732 1733 1734 1735 1736 1737 1738 1739 1740 1741 1742 1743 1744 1745 1746 1747 1748 1749 1750 1751 1752 1753 1754 1755 1756 1757 1758 1759 1760 1761 1762 1763 1764 1765 1766 1767 1768 1769 1770 1771 1772 1773 1774 1775 1776 1777 1778 1779 1780 1781 1782 1783 1784 1785 1786 1787 1788 1789 1790 1791 1792 1793 1794 1795 1796 1797 1798 1799 1800 1801 1802 1803 1804 1805 1806 1807 1808 1809 1810 1811 1812 1813 1814 1815 1816 1817 1818 1819 1820 1821 1822 1823 1824 1825 1826 1827 1828 1829 1830 1831 1832 1833 1834 1835 1836 1837 1838 1839 1840 1841 1842 1843 1844 1845 1846 1847 1848 1849 1850 1851 1852 1853 1854 1855 1856 1857 1858 1859 1860 1861 1862 1863 1864 1865 1866 1867 1868 1869 1870 1871 1872 1873 1874 1875 1876 1877 1878 1879 1880 1881 1882 1883 1884 1885 1886 1887 1888 1889 1890 1891 1892 1893 1894 1895 1896 1897 1898 1899 1900 1901 1902 1903 1904 1905 1906 1907 1908 1909 1910 1911 1912 1913 1914 1915 1916 1917 1918 1919 1920 1921 1922 1923 1924 1925 1926 1927 1928 1929 1930 1931 1932 1933 1934 1935 1936 1937 1938 1939 1940 1941 1942 1943 1944 1945 1946 1947 1948 1949 1950 1951 1952 1953 1954 1955 1956 1957 1958 1959 1960 1961 1962 1963 1964 1965 1966 1967 1968 1969 1970 1971 1972 1973 1974 1975 1976 1977 1978 1979 1980 1981 1982 1983 1984 1985 1986 1987 1988 1989 1990 1991 1992 1993 1994 1995 1996 1997 1998 1999 2000 2001 2002 2003 2004 2005 2006 2007 2008 2009 2010 2011 2012 2013 2014 2015 2016 2017 2018 2019 2020 2021 2022 2023 2024 2025 2026 2027 2028 2029 2030 2031 2032 2033 2034 2035 2036 2037 2038 2039 2040 2041 2042 2043 2044 2045 2046 2047 2048 2049 2050 2051 2052 2053 2054 2055 2056 2057 2058 2059 2060 2061 2062 2063 2064 2065 2066 2067 2068 2069 2070 2071 2072 2073 2074 2075 2076 2077 2078 2079 2080 2081 2082 2083 2084 2085 2086 2087 2088 2089 2090 2091 2092 2093 2094 2095 2096 2097 2098 2099 2100 2101 2102 2103 2104 2105 2106 2107 2108 2109 2110 2111 2112 2113 2114 2115 2116 2117 2118 2119 2120 2121 2122 2123 2124 2125 2126 2127 2128 2129 2130 2131 2132 2133 2134 2135 2136 2137 2138 2139 2140 2141 2142 2143 2144 2145 2146 2147 2148 2149 2150 2151 2152 2153 2154 2155 2156 2157 2158 2159 2160 2161 2162 2163 2164 2165 2166 2167 2168 2169 2170 2171 2172 2173 2174 2175 2176 2177 2178 2179 2180 2181 2182 2183 2184 2185 2186 2187 2188 2189 2190 2191 2192 2193 2194 2195 2196 2197 2198 2199 2200 2201 2202 2203 2204 2205 2206 2207 2208 2209 2210 2211 2212 2213 2214 2215 2216 2217 2218 2219 2220 2221 2222 2223 2224 2225 2226 2227 2228 2229 2230 2231 2232 2233 2234 2235 2236 2237 2238 2239 2240 2241 2242 2243 2244 2245 2246 2247 2248 2249 2250 2251 2252 2253 2254 2255 2256 2257 2258 2259 2260 2261 2262 2263 2264 2265 2266 2267 2268 2269 2270 2271 2272 2273 2274 2275 2276 2277 2278 2279 2280 2281 2282 2283 2284 2285 2286 2287 2288 2289 2290 2291 2292 2293 2294 2295 2296 2297 2298 2299 2300 2301 2302 2303 2304 2305 2306 2307 2308 2309 2310 2311 2312 2313 2314 2315 2316 2317 2318 2319 2320 2321 2322 2323 2324 2325 2326 2327 2328 2329 2330 2331 2332 2333 2334 2335 2336 2337 2338 2339 2340 2341 2342 2343 2344 2345 2346 2347 2348 2349 2350 2351 2352 2353 2354 2355 2356 2357 2358 2359 2360 2361 2362 2363 2364 2365 2366 2367 2368 2369 2370 2371 2372 2373 2374 2375 2376 2377 2378 2379 2380 2381 2382 2383 2384 2385 2386 2387 2388 2389 2390 2391 2392 2393 2394 2395 2396 2397 2398 2399 2400 2401 2402 2403 2404 2405 2406 2407 2408 2409 2410 2411 2412 2413 2414 2415 2416 2417 2418 2419 2420 2421 2422 2423 2424 2425 2426 2427 2428 2429 2430 2431 2432 2433 2434 2435 2436 2437 2438 2439 2440 2441 2442 2443 2444 2445 2446 2447 2448 2449 2450 2451 2452 2453 2454 2455 2456 2457 2458 2459 2460 2461 2462 2463 2464 2465 2466 2467 2468 2469 2470 2471 2472 2473 2474 2475 2476 2477 2478 2479 2480 2481 2482 2483 2484 2485 2486 2487 2488 2489 2490 2491 2492 2493 2494 2495 2496 2497 2498 2499 2500 2501 2502 2503 2504 2505 2506 2507 2508 2509 2510 2511 2512 2513 2514 2515 2516 2517 2518 2519 2520 2521 2522 2523 2524 2525 2526 2527 2528 2529 2530 2531 2532 2533 2534 2535 2536 2537 2538 2539 2540 2541 2542 2543 2544 2545 2546 2547 2548 2549 2550 2551 2552 2553 2554 2555 2556 2557 2558 2559 2560 2561 2562 2563 2564 2565 2566 2567 2568 2569 2570 2571 2572 2573 2574 2575 2576 2577 2578 2579 2580 2581 2582 2583 2584 2585 2586 2587 2588 2589 2590 2591 2592 2593 2594 2595 2596 2597 2598 2599 2600 2601 2602 2603 2604 2605 2606 2607 2608 2609 2610 2611 2612 2613 2614 2615 2616 2617 2618 2619 2620 2621 2622 2623 2624 2625 2626 2627 2628 2629 2630 2631 2632 2633 2634 2635 2636 2637 2638 2639 2640 2641 2642 2643 2644 2645 2646 2647 2648 2649 2650 2651 2652 2653 2654 2655 2656 2657 2658 2659 2660 2661 2662 2663 2664 2665 2666 2667 2668 2669 2670 2671 2672 2673 2674 2675 2676 2677 2678 2679 2680 2681 2682 2683 2684 2685 2686 2687 2688 2689 2690 2691 2692 2693 2694 2695 2696 2697 2698 2699 2700 2701 2702 2703 2704 2705 2706 2707 2708 2709 2710 2711 2712 2713 2714 2715 2716 2717 2718 2719 2720 2721 2722 2723 2724 2725 2726 2727 2728 2729 2730 2731 2732 2733 2734 2735 2736 2737 2738 2739 2740 2741 2742 2743 2744 2745 2746 2747 2748 2749 2750 2751 2752 2753 2754 2755 2756 2757 2758 2759 2760 2761 2762 2763 2764 2765 2766 2767 2768 2769 2770 2771 2772 2773 2774 2775 2776 2777 2778 2779 2780 2781 2782 2783 2784 2785 2786 2787 2788 2789 2790 2791 2792 2793 2794 2795 2796 2797 2798 2799 2800 2801 2802 2803 2804 2805 2806 2807 2808 2809 2810 2811 2812 2813 2814 2815 2816 2817 2818 2819 2820 2821 2822 2823 2824 2825 2826 2827 2828 2829 2830 2831 2832 2833 2834 2835 2836 2837 2838 2839 2840 2841 2842 2843 2844 2845 2846 2847 2848 2849 2850 2851 2852 2853 2854 2855 2856 2857 2858 2859 2860 2861 2862 2863 2864 2865 2866 2867 2868 2869 2870 2871 2872 2873 2874 2875 2876 2877 2878 2879 2880 2881 2882 2883 2884 2885 2886 2887 2888 2889 2890 2891 2892 2893 2894 2895 2896 2897 2898 2899 2900 2901 2902 2903 2904 2905 2906 2907 2908 2909 2910 2911 2912 2913 2914 2915 2916 2917 2918 2919 2920 2921 2922 2923 2924 2925 2926 2927 2928 2929 2930 2931 2932 2933 2934 2935 2936 2937 2938 2939 2940 2941 2942 2943 2944 2945 2946 2947 2948 2949 2950 2951 2952 2953 2954 2955 2956 2957 2958 2959 2960 2961 2962 2963 2964 2965 2966 2967 2968 2969 2970 2971 2972 2973 2974 2975 2976 2977 2978 2979 2980 2981 2982 2983 2984 2985 2986 2987 2988 2989 2990 2991 2992 2993 2994 2995 2996 2997 2998 2999 3000 3001 3002 3003 3004 3005 3006 3007 3008 3009 3010 3011 3012 3013 3014 3015 3016 3017 3018 3019 3020 3021 3022 3023 3024 3025 3026 3027 3028 3029 3030 3031 3032 3033 3034 3035 3036 3037 3038 3039 3040 3041 3042 3043 3044 3045 3046 3047 3048 3049 3050 3051 3052 3053 3054 3055 3056 3057 3058 3059 3060 3061 3062 3063 3064 3065 3066 3067 3068 3069 3070 3071 3072 3073 3074 3075 3076 3077 3078 3079 3080 3081 3082 3083 3084 3085 3086 3087 3088 3089 3090 3091 3092 3093 3094 3095 3096 3097 3098 3099 3100 3101 3102 3103 3104 3105 3106 3107 3108 3109 3110 3111 3112 3113 3114 3115 3116 3117 3118 3119 3120 3121 3122 3123 3124 3125 3126 3127 3128 3129 3130 3131 3132 3133 3134 3135 3136 3137 3138 3139 3140 3141 3142 3143 3144 3145 3146 3147 3148 3149 3150 3151 3152 3153 3154 3155 3156 3157 3158 3159 3160 3161 3162 3163 3164 3165 3166 3167 3168 3169 3170 3171 3172 3173 3174 3175 3176 3177 3178 3179 3180 3181 3182 3183 3184 3185 3186 3187 3188 3189 3190 3191 3192 3193 3194 3195 3196 3197 3198 3199 3200 3201 3202 3203 3204 3205 3206 3207 3208 3209 3210 3211 3212 3213 3214 3215 3216 3217 3218 3219 3220 3221 3222 3223 3224 3225 3226 3227 3228 3229 3230 3231 3232 3233 3234 3235 3236 3237 3238 3239 3240 3241 3242 3243 3244 3245 3246 3247 3248 3249 3250 3251 3252 3253 3254 3255 3256 3257 3258 3259 3260 3261 3262 3263 3264 3265 3266 3267 3268 3269 3270 3271 3272 3273 3274 3275 3276 3277 3278 3279 3280 3281 3282 3283 3284 3285 3286 3287 3288 3289 3290 3291 3292 3293 3294 3295 3296 3297 3298 3299 3300 3301 3302 3303 3304 3305 3306 3307 3308 3309 3310 3311 3312 3313 3314 3315 3316 3317 3318 3319 3320 3321 3322 3323 3324 3325 3326 3327 3328 3329 3330 3331 3332 3333 3334 3335 3336 3337 3338 3339 3340 3341 3342 3343 3344 3345 3346 3347 3348 3349 3350 3351 3352 3353 3354 3355 3356 3357 3358 3359 3360 3361 3362 3363 3364 3365 3366 3367 3368 3369 3370 3371 3372 3373 3374 3375 3376 3377 3378 3379 3380 3381 3382 3383 3384 3385 3386 3387 3388 3389 3390 3391 3392 3393 3394 3395 3396 3397 3398 3399 3400 3401 3402 3403 3404 3405 3406 3407 3408 3409 3410 3411 3412 3413 3414 3415 3416 3417 3418 3419 3420 3421 3422 3423 3424 3425 3426 3427 3428 3429 3430 3431 3432 3433 3434 3435 3436 3437 3438 3439 3440 3441 3442 3443 3444 3445 3446 3447 3448 3449 3450 3451 3452 3453 3454 3455 3456 3457 3458 3459 3460 3461 3462 3463 3464 3465 3466 3467 3468 3469 3470 3471 3472 3473 3474 3475 3476 3477 3478 3479 3480 3481 3482 3483 3484 3485 3486 3487 3488 3489 3490 3491 3492 3493 3494 3495 3496 3497 3498 3499 3500 3501 3502 3503 3504 3505 3506 3507 3508 3509 3510 3511 3512 3513 3514 3515 3516 3517 3518 3519 3520 3521 3522 3523 3524 3525 3526 3527 3528 3529 3530 3531 3532 3533 3534 3535 3536 3537 3538 3539 3540 | // Copyright 2022 DeepMind Technologies Limited
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
// DO NOT EDIT. THIS FILE IS AUTOMATICALLY GENERATED.
// Error: C reference not found
// NOLINTBEGIN
typedef enum mjtState_ { // state elements
mjSTATE_TIME = 1<<0, // time
mjSTATE_QPOS = 1<<1, // position
mjSTATE_QVEL = 1<<2, // velocity
mjSTATE_ACT = 1<<3, // actuator activation
mjSTATE_WARMSTART = 1<<4, // acceleration used for warmstart
mjSTATE_CTRL = 1<<5, // control
mjSTATE_QFRC_APPLIED = 1<<6, // applied generalized force
mjSTATE_XFRC_APPLIED = 1<<7, // applied Cartesian force/torque
mjSTATE_EQ_ACTIVE = 1<<8, // enable/disable constraints
mjSTATE_MOCAP_POS = 1<<9, // positions of mocap bodies
mjSTATE_MOCAP_QUAT = 1<<10, // orientations of mocap bodies
mjSTATE_USERDATA = 1<<11, // user data
mjSTATE_PLUGIN = 1<<12, // plugin state
mjNSTATE = 13, // number of state elements
// convenience values for commonly used state specifications
mjSTATE_PHYSICS = mjSTATE_QPOS | mjSTATE_QVEL | mjSTATE_ACT,
mjSTATE_FULLPHYSICS = mjSTATE_TIME | mjSTATE_PHYSICS | mjSTATE_PLUGIN,
mjSTATE_USER = mjSTATE_CTRL | mjSTATE_QFRC_APPLIED | mjSTATE_XFRC_APPLIED |
mjSTATE_EQ_ACTIVE | mjSTATE_MOCAP_POS | mjSTATE_MOCAP_QUAT |
mjSTATE_USERDATA,
mjSTATE_INTEGRATION = mjSTATE_FULLPHYSICS | mjSTATE_USER | mjSTATE_WARMSTART
} mjtState;
typedef enum mjtWarning_ { // warning types
mjWARN_INERTIA = 0, // (near) singular inertia matrix
mjWARN_CONTACTFULL, // too many contacts in contact list
mjWARN_CNSTRFULL, // too many constraints
mjWARN_VGEOMFULL, // too many visual geoms
mjWARN_BADQPOS, // bad number in qpos
mjWARN_BADQVEL, // bad number in qvel
mjWARN_BADQACC, // bad number in qacc
mjWARN_BADCTRL, // bad number in ctrl
mjNWARNING // number of warnings
} mjtWarning;
typedef enum mjtTimer_ { // internal timers
// main api
mjTIMER_STEP = 0, // step
mjTIMER_FORWARD, // forward
mjTIMER_INVERSE, // inverse
// breakdown of step/forward
mjTIMER_POSITION, // fwdPosition
mjTIMER_VELOCITY, // fwdVelocity
mjTIMER_ACTUATION, // fwdActuation
mjTIMER_CONSTRAINT, // fwdConstraint
mjTIMER_ADVANCE, // mj_Euler, mj_implicit
// breakdown of fwdPosition
mjTIMER_POS_KINEMATICS, // kinematics, com, tendon, transmission
mjTIMER_POS_INERTIA, // inertia computations
mjTIMER_POS_COLLISION, // collision detection
mjTIMER_POS_MAKE, // make constraints
mjTIMER_POS_PROJECT, // project constraints
// breakdown of mj_collision
mjTIMER_COL_BROAD, // broadphase
mjTIMER_COL_NARROW, // narrowphase
mjNTIMER // number of timers
} mjtTimer;
struct mjContact_ { // result of collision detection functions
// contact parameters set by near-phase collision function
mjtNum dist; // distance between nearest points; neg: penetration
mjtNum pos[3]; // position of contact point: midpoint between geoms
mjtNum frame[9]; // normal is in [0-2], points from geom[0] to geom[1]
// contact parameters set by mj_collideGeoms
mjtNum includemargin; // include if dist<includemargin=margin-gap
mjtNum friction[5]; // tangent1, 2, spin, roll1, 2
mjtNum solref[mjNREF]; // constraint solver reference, normal direction
mjtNum solreffriction[mjNREF]; // constraint solver reference, friction directions
mjtNum solimp[mjNIMP]; // constraint solver impedance
// internal storage used by solver
mjtNum mu; // friction of regularized cone, set by mj_makeConstraint
mjtNum H[36]; // cone Hessian, set by mj_constraintUpdate
// contact descriptors set by mj_collideXXX
int dim; // contact space dimensionality: 1, 3, 4 or 6
int geom1; // id of geom 1; deprecated, use geom[0]
int geom2; // id of geom 2; deprecated, use geom[1]
int geom[2]; // geom ids; -1 for flex
int flex[2]; // flex ids; -1 for geom
int elem[2]; // element ids; -1 for geom or flex vertex
int vert[2]; // vertex ids; -1 for geom or flex element
// flag set by mj_setContact or mj_instantiateContact
int exclude; // 0: include, 1: in gap, 2: fused, 3: no dofs
// address computed by mj_instantiateContact
int efc_address; // address in efc; -1: not included
};
typedef struct mjContact_ mjContact;
struct mjWarningStat_ { // warning statistics
int lastinfo; // info from last warning
int number; // how many times was warning raised
};
typedef struct mjWarningStat_ mjWarningStat;
struct mjTimerStat_ { // timer statistics
mjtNum duration; // cumulative duration
int number; // how many times was timer called
};
typedef struct mjTimerStat_ mjTimerStat;
struct mjSolverStat_ { // per-iteration solver statistics
mjtNum improvement; // cost reduction, scaled by 1/trace(M(qpos0))
mjtNum gradient; // gradient norm (primal only, scaled)
mjtNum lineslope; // slope in linesearch
int nactive; // number of active constraints
int nchange; // number of constraint state changes
int neval; // number of cost evaluations in line search
int nupdate; // number of Cholesky updates in line search
};
typedef struct mjSolverStat_ mjSolverStat;
struct mjData_ {
// constant sizes
size_t narena; // size of the arena in bytes (inclusive of the stack)
size_t nbuffer; // size of main buffer in bytes
int nplugin; // number of plugin instances
// stack pointer
size_t pstack; // first available byte in stack
size_t pbase; // value of pstack when mj_markStack was last called
// arena pointer
size_t parena; // first available byte in arena
// memory utilization statistics
size_t maxuse_stack; // maximum stack allocation in bytes
size_t maxuse_threadstack[mjMAXTHREAD]; // maximum stack allocation per thread in bytes
size_t maxuse_arena; // maximum arena allocation in bytes
int maxuse_con; // maximum number of contacts
int maxuse_efc; // maximum number of scalar constraints
// solver statistics
mjSolverStat solver[mjNISLAND*mjNSOLVER]; // solver statistics per island, per iteration
int solver_niter[mjNISLAND]; // number of solver iterations, per island
int solver_nnz[mjNISLAND]; // number of nonzeros in Hessian or efc_AR, per island
mjtNum solver_fwdinv[2]; // forward-inverse comparison: qfrc, efc
// diagnostics
mjWarningStat warning[mjNWARNING]; // warning statistics
mjTimerStat timer[mjNTIMER]; // timer statistics
// variable sizes
int ncon; // number of detected contacts
int ne; // number of equality constraints
int nf; // number of friction constraints
int nl; // number of limit constraints
int nefc; // number of constraints
int nJ; // number of non-zeros in constraint Jacobian
int nA; // number of non-zeros in constraint inverse inertia matrix
int nisland; // number of detected constraint islands
int nidof; // number of dofs in all islands
// global properties
mjtNum time; // simulation time
mjtNum energy[2]; // potential, kinetic energy
//-------------------- end of info header
// buffers
void* buffer; // main buffer; all pointers point in it (nbuffer bytes)
void* arena; // arena+stack buffer (narena bytes)
//-------------------- main inputs and outputs of the computation
// state
mjtNum* qpos; // position (nq x 1)
mjtNum* qvel; // velocity (nv x 1)
mjtNum* act; // actuator activation (na x 1)
mjtNum* qacc_warmstart; // acceleration used for warmstart (nv x 1)
mjtNum* plugin_state; // plugin state (npluginstate x 1)
// control
mjtNum* ctrl; // control (nu x 1)
mjtNum* qfrc_applied; // applied generalized force (nv x 1)
mjtNum* xfrc_applied; // applied Cartesian force/torque (nbody x 6)
mjtByte* eq_active; // enable/disable constraints (neq x 1)
// mocap data
mjtNum* mocap_pos; // positions of mocap bodies (nmocap x 3)
mjtNum* mocap_quat; // orientations of mocap bodies (nmocap x 4)
// dynamics
mjtNum* qacc; // acceleration (nv x 1)
mjtNum* act_dot; // time-derivative of actuator activation (na x 1)
// user data
mjtNum* userdata; // user data, not touched by engine (nuserdata x 1)
// sensors
mjtNum* sensordata; // sensor data array (nsensordata x 1)
// plugins
int* plugin; // copy of m->plugin, required for deletion (nplugin x 1)
uintptr_t* plugin_data; // pointer to plugin-managed data structure (nplugin x 1)
//-------------------- POSITION dependent
// computed by mj_fwdPosition/mj_kinematics
mjtNum* xpos; // Cartesian position of body frame (nbody x 3)
mjtNum* xquat; // Cartesian orientation of body frame (nbody x 4)
mjtNum* xmat; // Cartesian orientation of body frame (nbody x 9)
mjtNum* xipos; // Cartesian position of body com (nbody x 3)
mjtNum* ximat; // Cartesian orientation of body inertia (nbody x 9)
mjtNum* xanchor; // Cartesian position of joint anchor (njnt x 3)
mjtNum* xaxis; // Cartesian joint axis (njnt x 3)
mjtNum* geom_xpos; // Cartesian geom position (ngeom x 3)
mjtNum* geom_xmat; // Cartesian geom orientation (ngeom x 9)
mjtNum* site_xpos; // Cartesian site position (nsite x 3)
mjtNum* site_xmat; // Cartesian site orientation (nsite x 9)
mjtNum* cam_xpos; // Cartesian camera position (ncam x 3)
mjtNum* cam_xmat; // Cartesian camera orientation (ncam x 9)
mjtNum* light_xpos; // Cartesian light position (nlight x 3)
mjtNum* light_xdir; // Cartesian light direction (nlight x 3)
// computed by mj_fwdPosition/mj_comPos
mjtNum* subtree_com; // center of mass of each subtree (nbody x 3)
mjtNum* cdof; // com-based motion axis of each dof (rot:lin) (nv x 6)
mjtNum* cinert; // com-based body inertia and mass (nbody x 10)
// computed by mj_fwdPosition/mj_flex
mjtNum* flexvert_xpos; // Cartesian flex vertex positions (nflexvert x 3)
mjtNum* flexelem_aabb; // flex element bounding boxes (center, size) (nflexelem x 6)
int* flexedge_J_rownnz; // number of non-zeros in Jacobian row (nflexedge x 1)
int* flexedge_J_rowadr; // row start address in colind array (nflexedge x 1)
int* flexedge_J_colind; // column indices in sparse Jacobian (nflexedge x nv)
mjtNum* flexedge_J; // flex edge Jacobian (nflexedge x nv)
mjtNum* flexedge_length; // flex edge lengths (nflexedge x 1)
// computed by mj_fwdPosition/mj_tendon
int* ten_wrapadr; // start address of tendon's path (ntendon x 1)
int* ten_wrapnum; // number of wrap points in path (ntendon x 1)
int* ten_J_rownnz; // number of non-zeros in Jacobian row (ntendon x 1)
int* ten_J_rowadr; // row start address in colind array (ntendon x 1)
int* ten_J_colind; // column indices in sparse Jacobian (ntendon x nv)
mjtNum* ten_J; // tendon Jacobian (ntendon x nv)
mjtNum* ten_length; // tendon lengths (ntendon x 1)
int* wrap_obj; // geom id; -1: site; -2: pulley (nwrap x 2)
mjtNum* wrap_xpos; // Cartesian 3D points in all paths (nwrap x 6)
// computed by mj_fwdPosition/mj_transmission
mjtNum* actuator_length; // actuator lengths (nu x 1)
int* moment_rownnz; // number of non-zeros in actuator_moment row (nu x 1)
int* moment_rowadr; // row start address in colind array (nu x 1)
int* moment_colind; // column indices in sparse Jacobian (nJmom x 1)
mjtNum* actuator_moment; // actuator moments (nJmom x 1)
// computed by mj_fwdPosition/mj_makeM
mjtNum* crb; // com-based composite inertia and mass (nbody x 10)
mjtNum* qM; // inertia (sparse) (nM x 1)
mjtNum* M; // reduced inertia (compressed sparse row) (nC x 1)
// computed by mj_fwdPosition/mj_factorM
mjtNum* qLD; // L'*D*L factorization of M (sparse) (nC x 1)
mjtNum* qLDiagInv; // 1/diag(D) (nv x 1)
// computed by mj_collisionTree
mjtNum* bvh_aabb_dyn; // global bounding box (center, size) (nbvhdynamic x 6)
mjtByte* bvh_active; // was bounding volume checked for collision (nbvh x 1)
//-------------------- POSITION, VELOCITY dependent
// computed by mj_fwdVelocity
mjtNum* flexedge_velocity; // flex edge velocities (nflexedge x 1)
mjtNum* ten_velocity; // tendon velocities (ntendon x 1)
mjtNum* actuator_velocity; // actuator velocities (nu x 1)
// computed by mj_fwdVelocity/mj_comVel
mjtNum* cvel; // com-based velocity (rot:lin) (nbody x 6)
mjtNum* cdof_dot; // time-derivative of cdof (rot:lin) (nv x 6)
// computed by mj_fwdVelocity/mj_rne (without acceleration)
mjtNum* qfrc_bias; // C(qpos,qvel) (nv x 1)
// computed by mj_fwdVelocity/mj_passive
mjtNum* qfrc_spring; // passive spring force (nv x 1)
mjtNum* qfrc_damper; // passive damper force (nv x 1)
mjtNum* qfrc_gravcomp; // passive gravity compensation force (nv x 1)
mjtNum* qfrc_fluid; // passive fluid force (nv x 1)
mjtNum* qfrc_passive; // total passive force (nv x 1)
// computed by mj_sensorVel/mj_subtreeVel if needed
mjtNum* subtree_linvel; // linear velocity of subtree com (nbody x 3)
mjtNum* subtree_angmom; // angular momentum about subtree com (nbody x 3)
// computed by mj_Euler or mj_implicit
mjtNum* qH; // L'*D*L factorization of modified M (nC x 1)
mjtNum* qHDiagInv; // 1/diag(D) of modified M (nv x 1)
// computed by mj_resetData
int* B_rownnz; // body-dof: non-zeros in each row (nbody x 1)
int* B_rowadr; // body-dof: address of each row in B_colind (nbody x 1)
int* B_colind; // body-dof: column indices of non-zeros (nB x 1)
int* M_rownnz; // reduced inertia: non-zeros in each row (nv x 1)
int* M_rowadr; // reduced inertia: address of each row in M_colind (nv x 1)
int* M_colind; // reduced inertia: column indices of non-zeros (nC x 1)
int* mapM2M; // index mapping from qM to M (nC x 1)
int* D_rownnz; // full inertia: non-zeros in each row (nv x 1)
int* D_rowadr; // full inertia: address of each row in D_colind (nv x 1)
int* D_diag; // full inertia: index of diagonal element (nv x 1)
int* D_colind; // full inertia: column indices of non-zeros (nD x 1)
int* mapM2D; // index mapping from qM to D (nD x 1)
int* mapD2M; // index mapping from D to qM (nM x 1)
// computed by mj_implicit/mj_derivative
mjtNum* qDeriv; // d (passive + actuator - bias) / d qvel (nD x 1)
// computed by mj_implicit/mju_factorLUSparse
mjtNum* qLU; // sparse LU of (qM - dt*qDeriv) (nD x 1)
//-------------------- POSITION, VELOCITY, CONTROL/ACCELERATION dependent
// computed by mj_fwdActuation
mjtNum* actuator_force; // actuator force in actuation space (nu x 1)
mjtNum* qfrc_actuator; // actuator force (nv x 1)
// computed by mj_fwdAcceleration
mjtNum* qfrc_smooth; // net unconstrained force (nv x 1)
mjtNum* qacc_smooth; // unconstrained acceleration (nv x 1)
// computed by mj_fwdConstraint/mj_inverse
mjtNum* qfrc_constraint; // constraint force (nv x 1)
// computed by mj_inverse
mjtNum* qfrc_inverse; // net external force; should equal:
// qfrc_applied + J'*xfrc_applied + qfrc_actuator (nv x 1)
// computed by mj_sensorAcc/mj_rnePostConstraint if needed; rotation:translation format
mjtNum* cacc; // com-based acceleration (nbody x 6)
mjtNum* cfrc_int; // com-based interaction force with parent (nbody x 6)
mjtNum* cfrc_ext; // com-based external force on body (nbody x 6)
//-------------------- arena-allocated: POSITION dependent
// computed by mj_collision
mjContact* contact; // array of all detected contacts (ncon x 1)
// computed by mj_makeConstraint
int* efc_type; // constraint type (mjtConstraint) (nefc x 1)
int* efc_id; // id of object of specified type (nefc x 1)
int* efc_J_rownnz; // number of non-zeros in constraint Jacobian row (nefc x 1)
int* efc_J_rowadr; // row start address in colind array (nefc x 1)
int* efc_J_rowsuper; // number of subsequent rows in supernode (nefc x 1)
int* efc_J_colind; // column indices in constraint Jacobian (nJ x 1)
int* efc_JT_rownnz; // number of non-zeros in constraint Jacobian row T (nv x 1)
int* efc_JT_rowadr; // row start address in colind array T (nv x 1)
int* efc_JT_rowsuper; // number of subsequent rows in supernode T (nv x 1)
int* efc_JT_colind; // column indices in constraint Jacobian T (nJ x 1)
mjtNum* efc_J; // constraint Jacobian (nJ x 1)
mjtNum* efc_JT; // constraint Jacobian transposed (nJ x 1)
mjtNum* efc_pos; // constraint position (equality, contact) (nefc x 1)
mjtNum* efc_margin; // inclusion margin (contact) (nefc x 1)
mjtNum* efc_frictionloss; // frictionloss (friction) (nefc x 1)
mjtNum* efc_diagApprox; // approximation to diagonal of A (nefc x 1)
mjtNum* efc_KBIP; // stiffness, damping, impedance, imp' (nefc x 4)
mjtNum* efc_D; // constraint mass (nefc x 1)
mjtNum* efc_R; // inverse constraint mass (nefc x 1)
int* tendon_efcadr; // first efc address involving tendon; -1: none (ntendon x 1)
// computed by mj_island (island dof structure)
int* dof_island; // island id of this dof; -1: none (nv x 1)
int* island_nv; // number of dofs in this island (nisland x 1)
int* island_idofadr; // island start address in idof vector (nisland x 1)
int* island_dofadr; // island start address in dof vector (nisland x 1)
int* map_dof2idof; // map from dof to idof (nv x 1)
int* map_idof2dof; // map from idof to dof; >= nidof: unconstrained (nv x 1)
// computed by mj_island (dofs sorted by island)
mjtNum* ifrc_smooth; // net unconstrained force (nidof x 1)
mjtNum* iacc_smooth; // unconstrained acceleration (nidof x 1)
int* iM_rownnz; // inertia: non-zeros in each row (nidof x 1)
int* iM_rowadr; // inertia: address of each row in iM_colind (nidof x 1)
int* iM_colind; // inertia: column indices of non-zeros (nC x 1)
mjtNum* iM; // total inertia (sparse) (nC x 1)
mjtNum* iLD; // L'*D*L factorization of M (sparse) (nC x 1)
mjtNum* iLDiagInv; // 1/diag(D) (nidof x 1)
mjtNum* iacc; // acceleration (nidof x 1)
// computed by mj_island (island constraint structure)
int* efc_island; // island id of this constraint (nefc x 1)
int* island_ne; // number of equality constraints in island (nisland x 1)
int* island_nf; // number of friction constraints in island (nisland x 1)
int* island_nefc; // number of constraints in island (nisland x 1)
int* island_iefcadr; // start address in iefc vector (nisland x 1)
int* map_efc2iefc; // map from efc to iefc (nefc x 1)
int* map_iefc2efc; // map from iefc to efc (nefc x 1)
// computed by mj_island (constraints sorted by island)
int* iefc_type; // constraint type (mjtConstraint) (nefc x 1)
int* iefc_id; // id of object of specified type (nefc x 1)
int* iefc_J_rownnz; // number of non-zeros in constraint Jacobian row (nefc x 1)
int* iefc_J_rowadr; // row start address in colind array (nefc x 1)
int* iefc_J_rowsuper; // number of subsequent rows in supernode (nefc x 1)
int* iefc_J_colind; // column indices in constraint Jacobian (nJ x 1)
int* iefc_JT_rownnz; // number of non-zeros in constraint Jacobian row T (nidof x 1)
int* iefc_JT_rowadr; // row start address in colind array T (nidof x 1)
int* iefc_JT_rowsuper; // number of subsequent rows in supernode T (nidof x 1)
int* iefc_JT_colind; // column indices in constraint Jacobian T (nJ x 1)
mjtNum* iefc_J; // constraint Jacobian (nJ x 1)
mjtNum* iefc_JT; // constraint Jacobian transposed (nJ x 1)
mjtNum* iefc_frictionloss; // frictionloss (friction) (nefc x 1)
mjtNum* iefc_D; // constraint mass (nefc x 1)
mjtNum* iefc_R; // inverse constraint mass (nefc x 1)
// computed by mj_projectConstraint (PGS solver)
int* efc_AR_rownnz; // number of non-zeros in AR (nefc x 1)
int* efc_AR_rowadr; // row start address in colind array (nefc x 1)
int* efc_AR_colind; // column indices in sparse AR (nA x 1)
mjtNum* efc_AR; // J*inv(M)*J' + R (nA x 1)
//-------------------- arena-allocated: POSITION, VELOCITY dependent
// computed by mj_fwdVelocity/mj_referenceConstraint
mjtNum* efc_vel; // velocity in constraint space: J*qvel (nefc x 1)
mjtNum* efc_aref; // reference pseudo-acceleration (nefc x 1)
//-------------------- arena-allocated: POSITION, VELOCITY, CONTROL/ACCELERATION dependent
// computed by mj_fwdConstraint/mj_inverse
mjtNum* efc_b; // linear cost term: J*qacc_smooth - aref (nefc x 1)
mjtNum* iefc_aref; // reference pseudo-acceleration (nefc x 1)
int* iefc_state; // constraint state (mjtConstraintState) (nefc x 1)
mjtNum* iefc_force; // constraint force in constraint space (nefc x 1)
int* efc_state; // constraint state (mjtConstraintState) (nefc x 1)
mjtNum* efc_force; // constraint force in constraint space (nefc x 1)
mjtNum* ifrc_constraint; // constraint force (nidof x 1)
// thread pool pointer
uintptr_t threadpool;
// compilation signature
uint64_t signature; // also held by the mjSpec that compiled the model
};
typedef struct mjData_ mjData;
typedef enum mjtDisableBit_ { // disable default feature bitflags
mjDSBL_CONSTRAINT = 1<<0, // entire constraint solver
mjDSBL_EQUALITY = 1<<1, // equality constraints
mjDSBL_FRICTIONLOSS = 1<<2, // joint and tendon frictionloss constraints
mjDSBL_LIMIT = 1<<3, // joint and tendon limit constraints
mjDSBL_CONTACT = 1<<4, // contact constraints
mjDSBL_PASSIVE = 1<<5, // passive forces
mjDSBL_GRAVITY = 1<<6, // gravitational forces
mjDSBL_CLAMPCTRL = 1<<7, // clamp control to specified range
mjDSBL_WARMSTART = 1<<8, // warmstart constraint solver
mjDSBL_FILTERPARENT = 1<<9, // remove collisions with parent body
mjDSBL_ACTUATION = 1<<10, // apply actuation forces
mjDSBL_REFSAFE = 1<<11, // integrator safety: make ref[0]>=2*timestep
mjDSBL_SENSOR = 1<<12, // sensors
mjDSBL_MIDPHASE = 1<<13, // mid-phase collision filtering
mjDSBL_EULERDAMP = 1<<14, // implicit integration of joint damping in Euler integrator
mjDSBL_AUTORESET = 1<<15, // automatic reset when numerical issues are detected
mjDSBL_NATIVECCD = 1<<16, // native convex collision detection
mjNDISABLE = 17 // number of disable flags
} mjtDisableBit;
typedef enum mjtEnableBit_ { // enable optional feature bitflags
mjENBL_OVERRIDE = 1<<0, // override contact parameters
mjENBL_ENERGY = 1<<1, // energy computation
mjENBL_FWDINV = 1<<2, // record solver statistics
mjENBL_INVDISCRETE = 1<<3, // discrete-time inverse dynamics
// experimental features:
mjENBL_MULTICCD = 1<<4, // multi-point convex collision detection
mjENBL_ISLAND = 1<<5, // constraint island discovery
mjNENABLE = 6 // number of enable flags
} mjtEnableBit;
typedef enum mjtJoint_ { // type of degree of freedom
mjJNT_FREE = 0, // global position and orientation (quat) (7)
mjJNT_BALL, // orientation (quat) relative to parent (4)
mjJNT_SLIDE, // sliding distance along body-fixed axis (1)
mjJNT_HINGE // rotation angle (rad) around body-fixed axis (1)
} mjtJoint;
typedef enum mjtGeom_ { // type of geometric shape
// regular geom types
mjGEOM_PLANE = 0, // plane
mjGEOM_HFIELD, // height field
mjGEOM_SPHERE, // sphere
mjGEOM_CAPSULE, // capsule
mjGEOM_ELLIPSOID, // ellipsoid
mjGEOM_CYLINDER, // cylinder
mjGEOM_BOX, // box
mjGEOM_MESH, // mesh
mjGEOM_SDF, // signed distance field
mjNGEOMTYPES, // number of regular geom types
// rendering-only geom types: not used in mjModel, not counted in mjNGEOMTYPES
mjGEOM_ARROW = 100, // arrow
mjGEOM_ARROW1, // arrow without wedges
mjGEOM_ARROW2, // arrow in both directions
mjGEOM_LINE, // line
mjGEOM_LINEBOX, // box with line edges
mjGEOM_FLEX, // flex
mjGEOM_SKIN, // skin
mjGEOM_LABEL, // text label
mjGEOM_TRIANGLE, // triangle
mjGEOM_NONE = 1001 // missing geom type
} mjtGeom;
typedef enum mjtCamLight_ { // tracking mode for camera and light
mjCAMLIGHT_FIXED = 0, // pos and rot fixed in body
mjCAMLIGHT_TRACK, // pos tracks body, rot fixed in global
mjCAMLIGHT_TRACKCOM, // pos tracks subtree com, rot fixed in body
mjCAMLIGHT_TARGETBODY, // pos fixed in body, rot tracks target body
mjCAMLIGHT_TARGETBODYCOM // pos fixed in body, rot tracks target subtree com
} mjtCamLight;
typedef enum mjtLightType_ { // type of light
mjLIGHT_SPOT = 0, // spot
mjLIGHT_DIRECTIONAL, // directional
mjLIGHT_POINT, // point
mjLIGHT_IMAGE, // image-based
} mjtLightType;
typedef enum mjtTexture_ { // type of texture
mjTEXTURE_2D = 0, // 2d texture, suitable for planes and hfields
mjTEXTURE_CUBE, // cube texture, suitable for all other geom types
mjTEXTURE_SKYBOX // cube texture used as skybox
} mjtTexture;
typedef enum mjtTextureRole_ { // role of texture map in rendering
mjTEXROLE_USER = 0, // unspecified
mjTEXROLE_RGB, // base color (albedo)
mjTEXROLE_OCCLUSION, // ambient occlusion
mjTEXROLE_ROUGHNESS, // roughness
mjTEXROLE_METALLIC, // metallic
mjTEXROLE_NORMAL, // normal (bump) map
mjTEXROLE_OPACITY, // transperancy
mjTEXROLE_EMISSIVE, // light emission
mjTEXROLE_RGBA, // base color, opacity
mjTEXROLE_ORM, // occlusion, roughness, metallic
mjNTEXROLE
} mjtTextureRole;
typedef enum mjtColorSpace_ { // type of color space encoding
mjCOLORSPACE_AUTO = 0, // attempts to autodetect color space, defaults to linear
mjCOLORSPACE_LINEAR, // linear color space
mjCOLORSPACE_SRGB // standard RGB color space
} mjtColorSpace;
typedef enum mjtIntegrator_ { // integrator mode
mjINT_EULER = 0, // semi-implicit Euler
mjINT_RK4, // 4th-order Runge Kutta
mjINT_IMPLICIT, // implicit in velocity
mjINT_IMPLICITFAST // implicit in velocity, no rne derivative
} mjtIntegrator;
typedef enum mjtCone_ { // type of friction cone
mjCONE_PYRAMIDAL = 0, // pyramidal
mjCONE_ELLIPTIC // elliptic
} mjtCone;
typedef enum mjtJacobian_ { // type of constraint Jacobian
mjJAC_DENSE = 0, // dense
mjJAC_SPARSE, // sparse
mjJAC_AUTO // dense if nv<60, sparse otherwise
} mjtJacobian;
typedef enum mjtSolver_ { // constraint solver algorithm
mjSOL_PGS = 0, // PGS (dual)
mjSOL_CG, // CG (primal)
mjSOL_NEWTON // Newton (primal)
} mjtSolver;
typedef enum mjtEq_ { // type of equality constraint
mjEQ_CONNECT = 0, // connect two bodies at a point (ball joint)
mjEQ_WELD, // fix relative position and orientation of two bodies
mjEQ_JOINT, // couple the values of two scalar joints with cubic
mjEQ_TENDON, // couple the lengths of two tendons with cubic
mjEQ_FLEX, // fix all edge lengths of a flex
mjEQ_DISTANCE // unsupported, will cause an error if used
} mjtEq;
typedef enum mjtWrap_ { // type of tendon wrap object
mjWRAP_NONE = 0, // null object
mjWRAP_JOINT, // constant moment arm
mjWRAP_PULLEY, // pulley used to split tendon
mjWRAP_SITE, // pass through site
mjWRAP_SPHERE, // wrap around sphere
mjWRAP_CYLINDER // wrap around (infinite) cylinder
} mjtWrap;
typedef enum mjtTrn_ { // type of actuator transmission
mjTRN_JOINT = 0, // force on joint
mjTRN_JOINTINPARENT, // force on joint, expressed in parent frame
mjTRN_SLIDERCRANK, // force via slider-crank linkage
mjTRN_TENDON, // force on tendon
mjTRN_SITE, // force on site
mjTRN_BODY, // adhesion force on a body's geoms
mjTRN_UNDEFINED = 1000 // undefined transmission type
} mjtTrn;
typedef enum mjtDyn_ { // type of actuator dynamics
mjDYN_NONE = 0, // no internal dynamics; ctrl specifies force
mjDYN_INTEGRATOR, // integrator: da/dt = u
mjDYN_FILTER, // linear filter: da/dt = (u-a) / tau
mjDYN_FILTEREXACT, // linear filter: da/dt = (u-a) / tau, with exact integration
mjDYN_MUSCLE, // piece-wise linear filter with two time constants
mjDYN_USER // user-defined dynamics type
} mjtDyn;
typedef enum mjtGain_ { // type of actuator gain
mjGAIN_FIXED = 0, // fixed gain
mjGAIN_AFFINE, // const + kp*length + kv*velocity
mjGAIN_MUSCLE, // muscle FLV curve computed by mju_muscleGain()
mjGAIN_USER // user-defined gain type
} mjtGain;
typedef enum mjtBias_ { // type of actuator bias
mjBIAS_NONE = 0, // no bias
mjBIAS_AFFINE, // const + kp*length + kv*velocity
mjBIAS_MUSCLE, // muscle passive force computed by mju_muscleBias()
mjBIAS_USER // user-defined bias type
} mjtBias;
typedef enum mjtObj_ { // type of MujoCo object
mjOBJ_UNKNOWN = 0, // unknown object type
mjOBJ_BODY, // body
mjOBJ_XBODY, // body, used to access regular frame instead of i-frame
mjOBJ_JOINT, // joint
mjOBJ_DOF, // dof
mjOBJ_GEOM, // geom
mjOBJ_SITE, // site
mjOBJ_CAMERA, // camera
mjOBJ_LIGHT, // light
mjOBJ_FLEX, // flex
mjOBJ_MESH, // mesh
mjOBJ_SKIN, // skin
mjOBJ_HFIELD, // heightfield
mjOBJ_TEXTURE, // texture
mjOBJ_MATERIAL, // material for rendering
mjOBJ_PAIR, // geom pair to include
mjOBJ_EXCLUDE, // body pair to exclude
mjOBJ_EQUALITY, // equality constraint
mjOBJ_TENDON, // tendon
mjOBJ_ACTUATOR, // actuator
mjOBJ_SENSOR, // sensor
mjOBJ_NUMERIC, // numeric
mjOBJ_TEXT, // text
mjOBJ_TUPLE, // tuple
mjOBJ_KEY, // keyframe
mjOBJ_PLUGIN, // plugin instance
mjNOBJECT, // number of object types
// meta elements, do not appear in mjModel
mjOBJ_FRAME = 100, // frame
mjOBJ_DEFAULT, // default
mjOBJ_MODEL // entire model
} mjtObj;
typedef enum mjtConstraint_ { // type of constraint
mjCNSTR_EQUALITY = 0, // equality constraint
mjCNSTR_FRICTION_DOF, // dof friction
mjCNSTR_FRICTION_TENDON, // tendon friction
mjCNSTR_LIMIT_JOINT, // joint limit
mjCNSTR_LIMIT_TENDON, // tendon limit
mjCNSTR_CONTACT_FRICTIONLESS, // frictionless contact
mjCNSTR_CONTACT_PYRAMIDAL, // frictional contact, pyramidal friction cone
mjCNSTR_CONTACT_ELLIPTIC // frictional contact, elliptic friction cone
} mjtConstraint;
typedef enum mjtConstraintState_ { // constraint state
mjCNSTRSTATE_SATISFIED = 0, // constraint satisfied, zero cost (limit, contact)
mjCNSTRSTATE_QUADRATIC, // quadratic cost (equality, friction, limit, contact)
mjCNSTRSTATE_LINEARNEG, // linear cost, negative side (friction)
mjCNSTRSTATE_LINEARPOS, // linear cost, positive side (friction)
mjCNSTRSTATE_CONE // squared distance to cone cost (elliptic contact)
} mjtConstraintState;
typedef enum mjtSensor_ { // type of sensor
// common robotic sensors, attached to a site
mjSENS_TOUCH = 0, // scalar contact normal forces summed over sensor zone
mjSENS_ACCELEROMETER, // 3D linear acceleration, in local frame
mjSENS_VELOCIMETER, // 3D linear velocity, in local frame
mjSENS_GYRO, // 3D angular velocity, in local frame
mjSENS_FORCE, // 3D force between site's body and its parent body
mjSENS_TORQUE, // 3D torque between site's body and its parent body
mjSENS_MAGNETOMETER, // 3D magnetometer
mjSENS_RANGEFINDER, // scalar distance to nearest geom or site along z-axis
mjSENS_CAMPROJECTION, // pixel coordinates of a site in the camera image
// sensors related to scalar joints, tendons, actuators
mjSENS_JOINTPOS, // scalar joint position (hinge and slide only)
mjSENS_JOINTVEL, // scalar joint velocity (hinge and slide only)
mjSENS_TENDONPOS, // scalar tendon position
mjSENS_TENDONVEL, // scalar tendon velocity
mjSENS_ACTUATORPOS, // scalar actuator position
mjSENS_ACTUATORVEL, // scalar actuator velocity
mjSENS_ACTUATORFRC, // scalar actuator force
mjSENS_JOINTACTFRC, // scalar actuator force, measured at the joint
mjSENS_TENDONACTFRC, // scalar actuator force, measured at the tendon
// sensors related to ball joints
mjSENS_BALLQUAT, // 4D ball joint quaternion
mjSENS_BALLANGVEL, // 3D ball joint angular velocity
// joint and tendon limit sensors, in constraint space
mjSENS_JOINTLIMITPOS, // joint limit distance-margin
mjSENS_JOINTLIMITVEL, // joint limit velocity
mjSENS_JOINTLIMITFRC, // joint limit force
mjSENS_TENDONLIMITPOS, // tendon limit distance-margin
mjSENS_TENDONLIMITVEL, // tendon limit velocity
mjSENS_TENDONLIMITFRC, // tendon limit force
// sensors attached to an object with spatial frame: (x)body, geom, site, camera
mjSENS_FRAMEPOS, // 3D position
mjSENS_FRAMEQUAT, // 4D unit quaternion orientation
mjSENS_FRAMEXAXIS, // 3D unit vector: x-axis of object's frame
mjSENS_FRAMEYAXIS, // 3D unit vector: y-axis of object's frame
mjSENS_FRAMEZAXIS, // 3D unit vector: z-axis of object's frame
mjSENS_FRAMELINVEL, // 3D linear velocity
mjSENS_FRAMEANGVEL, // 3D angular velocity
mjSENS_FRAMELINACC, // 3D linear acceleration
mjSENS_FRAMEANGACC, // 3D angular acceleration
// sensors related to kinematic subtrees; attached to a body (which is the subtree root)
mjSENS_SUBTREECOM, // 3D center of mass of subtree
mjSENS_SUBTREELINVEL, // 3D linear velocity of subtree
mjSENS_SUBTREEANGMOM, // 3D angular momentum of subtree
// sensors of geometric relationships
mjSENS_INSIDESITE, // 1 if object is inside a site, 0 otherwise
mjSENS_GEOMDIST, // signed distance between two geoms
mjSENS_GEOMNORMAL, // normal direction between two geoms
mjSENS_GEOMFROMTO, // segment between two geoms
// global sensors
mjSENS_E_POTENTIAL, // potential energy
mjSENS_E_KINETIC, // kinetic energy
mjSENS_CLOCK, // simulation time
// plugin-controlled sensors
mjSENS_PLUGIN, // plugin-controlled
// user-defined sensor
mjSENS_USER // sensor data provided by mjcb_sensor callback
} mjtSensor;
typedef enum mjtStage_ { // computation stage
mjSTAGE_NONE = 0, // no computations
mjSTAGE_POS, // position-dependent computations
mjSTAGE_VEL, // velocity-dependent computations
mjSTAGE_ACC // acceleration/force-dependent computations
} mjtStage;
typedef enum mjtDataType_ { // data type for sensors
mjDATATYPE_REAL = 0, // real values, no constraints
mjDATATYPE_POSITIVE, // positive values; 0 or negative: inactive
mjDATATYPE_AXIS, // 3D unit vector
mjDATATYPE_QUATERNION // unit quaternion
} mjtDataType;
typedef enum mjtSameFrame_ { // frame alignment of bodies with their children
mjSAMEFRAME_NONE = 0, // no alignment
mjSAMEFRAME_BODY, // frame is same as body frame
mjSAMEFRAME_INERTIA, // frame is same as inertial frame
mjSAMEFRAME_BODYROT, // frame orientation is same as body orientation
mjSAMEFRAME_INERTIAROT // frame orientation is same as inertia orientation
} mjtSameFrame;
typedef enum mjtLRMode_ { // mode for actuator length range computation
mjLRMODE_NONE = 0, // do not process any actuators
mjLRMODE_MUSCLE, // process muscle actuators
mjLRMODE_MUSCLEUSER, // process muscle and user actuators
mjLRMODE_ALL // process all actuators
} mjtLRMode;
typedef enum mjtFlexSelf_ { // mode for flex selfcollide
mjFLEXSELF_NONE = 0, // no self-collisions
mjFLEXSELF_NARROW, // skip midphase, go directly to narrowphase
mjFLEXSELF_BVH, // use BVH in midphase (if midphase enabled)
mjFLEXSELF_SAP, // use SAP in midphase
mjFLEXSELF_AUTO // choose between BVH and SAP automatically
} mjtFlexSelf;
typedef enum mjtSDFType_ { // signed distance function (SDF) type
mjSDFTYPE_SINGLE = 0, // single SDF
mjSDFTYPE_INTERSECTION, // max(A, B)
mjSDFTYPE_MIDSURFACE, // A - B
mjSDFTYPE_COLLISION, // A + B + abs(max(A, B))
} mjtSDFType;
struct mjLROpt_ { // options for mj_setLengthRange()
// flags
int mode; // which actuators to process (mjtLRMode)
int useexisting; // use existing length range if available
int uselimit; // use joint and tendon limits if available
// algorithm parameters
mjtNum accel; // target acceleration used to compute force
mjtNum maxforce; // maximum force; 0: no limit
mjtNum timeconst; // time constant for velocity reduction; min 0.01
mjtNum timestep; // simulation timestep; 0: use mjOption.timestep
mjtNum inttotal; // total simulation time interval
mjtNum interval; // evaluation time interval (at the end)
mjtNum tolrange; // convergence tolerance (relative to range)
};
typedef struct mjLROpt_ mjLROpt;
struct mjVFS_ { // virtual file system for loading from memory
void* impl_; // internal pointer to VFS memory
};
typedef struct mjVFS_ mjVFS;
struct mjOption_ { // physics options
// timing parameters
mjtNum timestep; // timestep
mjtNum apirate; // update rate for remote API (Hz)
// solver parameters
mjtNum impratio; // ratio of friction-to-normal contact impedance
mjtNum tolerance; // main solver tolerance
mjtNum ls_tolerance; // CG/Newton linesearch tolerance
mjtNum noslip_tolerance; // noslip solver tolerance
mjtNum ccd_tolerance; // convex collision solver tolerance
// physical constants
mjtNum gravity[3]; // gravitational acceleration
mjtNum wind[3]; // wind (for lift, drag and viscosity)
mjtNum magnetic[3]; // global magnetic flux
mjtNum density; // density of medium
mjtNum viscosity; // viscosity of medium
// override contact solver parameters (if enabled)
mjtNum o_margin; // margin
mjtNum o_solref[mjNREF]; // solref
mjtNum o_solimp[mjNIMP]; // solimp
mjtNum o_friction[5]; // friction
// discrete settings
int integrator; // integration mode (mjtIntegrator)
int cone; // type of friction cone (mjtCone)
int jacobian; // type of Jacobian (mjtJacobian)
int solver; // solver algorithm (mjtSolver)
int iterations; // maximum number of main solver iterations
int ls_iterations; // maximum number of CG/Newton linesearch iterations
int noslip_iterations; // maximum number of noslip solver iterations
int ccd_iterations; // maximum number of convex collision solver iterations
int disableflags; // bit flags for disabling standard features
int enableflags; // bit flags for enabling optional features
int disableactuator; // bit flags for disabling actuators by group id
// sdf collision settings
int sdf_initpoints; // number of starting points for gradient descent
int sdf_iterations; // max number of iterations for gradient descent
};
typedef struct mjOption_ mjOption;
struct mjVisual_ { // visualization options
struct { // global parameters
int cameraid; // initial camera id (-1: free)
int orthographic; // is the free camera orthographic (0: no, 1: yes)
float fovy; // y field-of-view of free camera (orthographic ? length : degree)
float ipd; // inter-pupilary distance for free camera
float azimuth; // initial azimuth of free camera (degrees)
float elevation; // initial elevation of free camera (degrees)
float linewidth; // line width for wireframe and ray rendering
float glow; // glow coefficient for selected body
float realtime; // initial real-time factor (1: real time)
int offwidth; // width of offscreen buffer
int offheight; // height of offscreen buffer
int ellipsoidinertia; // geom for inertia visualization (0: box, 1: ellipsoid)
int bvactive; // visualize active bounding volumes (0: no, 1: yes)
} global;
struct { // rendering quality
int shadowsize; // size of shadowmap texture
int offsamples; // number of multisamples for offscreen rendering
int numslices; // number of slices for builtin geom drawing
int numstacks; // number of stacks for builtin geom drawing
int numquads; // number of quads for box rendering
} quality;
struct { // head light
float ambient[3]; // ambient rgb (alpha=1)
float diffuse[3]; // diffuse rgb (alpha=1)
float specular[3]; // specular rgb (alpha=1)
int active; // is headlight active
} headlight;
struct { // mapping
float stiffness; // mouse perturbation stiffness (space->force)
float stiffnessrot; // mouse perturbation stiffness (space->torque)
float force; // from force units to space units
float torque; // from torque units to space units
float alpha; // scale geom alphas when transparency is enabled
float fogstart; // OpenGL fog starts at fogstart * mjModel.stat.extent
float fogend; // OpenGL fog ends at fogend * mjModel.stat.extent
float znear; // near clipping plane = znear * mjModel.stat.extent
float zfar; // far clipping plane = zfar * mjModel.stat.extent
float haze; // haze ratio
float shadowclip; // directional light: shadowclip * mjModel.stat.extent
float shadowscale; // spot light: shadowscale * light.cutoff
float actuatortendon; // scale tendon width
} map;
struct { // scale of decor elements relative to mean body size
float forcewidth; // width of force arrow
float contactwidth; // contact width
float contactheight; // contact height
float connect; // autoconnect capsule width
float com; // com radius
float camera; // camera object
float light; // light object
float selectpoint; // selection point
float jointlength; // joint length
float jointwidth; // joint width
float actuatorlength; // actuator length
float actuatorwidth; // actuator width
float framelength; // bodyframe axis length
float framewidth; // bodyframe axis width
float constraint; // constraint width
float slidercrank; // slidercrank width
float frustum; // frustum zfar plane
} scale;
struct { // color of decor elements
float fog[4]; // fog
float haze[4]; // haze
float force[4]; // external force
float inertia[4]; // inertia box
float joint[4]; // joint
float actuator[4]; // actuator, neutral
float actuatornegative[4]; // actuator, negative limit
float actuatorpositive[4]; // actuator, positive limit
float com[4]; // center of mass
float camera[4]; // camera object
float light[4]; // light object
float selectpoint[4]; // selection point
float connect[4]; // auto connect
float contactpoint[4]; // contact point
float contactforce[4]; // contact force
float contactfriction[4]; // contact friction force
float contacttorque[4]; // contact torque
float contactgap[4]; // contact point in gap
float rangefinder[4]; // rangefinder ray
float constraint[4]; // constraint
float slidercrank[4]; // slidercrank
float crankbroken[4]; // used when crank must be stretched/broken
float frustum[4]; // camera frustum
float bv[4]; // bounding volume
float bvactive[4]; // active bounding volume
} rgba;
};
typedef struct mjVisual_ mjVisual;
struct mjStatistic_ { // model statistics (in qpos0)
mjtNum meaninertia; // mean diagonal inertia
mjtNum meanmass; // mean body mass
mjtNum meansize; // mean body size
mjtNum extent; // spatial extent
mjtNum center[3]; // center of model
};
typedef struct mjStatistic_ mjStatistic;
struct mjModel_ {
// ------------------------------- sizes
// sizes needed at mjModel construction
int nq; // number of generalized coordinates = dim(qpos)
int nv; // number of degrees of freedom = dim(qvel)
int nu; // number of actuators/controls = dim(ctrl)
int na; // number of activation states = dim(act)
int nbody; // number of bodies
int nbvh; // number of total bounding volumes in all bodies
int nbvhstatic; // number of static bounding volumes (aabb stored in mjModel)
int nbvhdynamic; // number of dynamic bounding volumes (aabb stored in mjData)
int noct; // number of total octree cells in all meshes
int njnt; // number of joints
int ngeom; // number of geoms
int nsite; // number of sites
int ncam; // number of cameras
int nlight; // number of lights
int nflex; // number of flexes
int nflexnode; // number of dofs in all flexes
int nflexvert; // number of vertices in all flexes
int nflexedge; // number of edges in all flexes
int nflexelem; // number of elements in all flexes
int nflexelemdata; // number of element vertex ids in all flexes
int nflexelemedge; // number of element edge ids in all flexes
int nflexshelldata; // number of shell fragment vertex ids in all flexes
int nflexevpair; // number of element-vertex pairs in all flexes
int nflextexcoord; // number of vertices with texture coordinates
int nmesh; // number of meshes
int nmeshvert; // number of vertices in all meshes
int nmeshnormal; // number of normals in all meshes
int nmeshtexcoord; // number of texcoords in all meshes
int nmeshface; // number of triangular faces in all meshes
int nmeshgraph; // number of ints in mesh auxiliary data
int nmeshpoly; // number of polygons in all meshes
int nmeshpolyvert; // number of vertices in all polygons
int nmeshpolymap; // number of polygons in vertex map
int nskin; // number of skins
int nskinvert; // number of vertices in all skins
int nskintexvert; // number of vertiex with texcoords in all skins
int nskinface; // number of triangular faces in all skins
int nskinbone; // number of bones in all skins
int nskinbonevert; // number of vertices in all skin bones
int nhfield; // number of heightfields
int nhfielddata; // number of data points in all heightfields
int ntex; // number of textures
int ntexdata; // number of bytes in texture rgb data
int nmat; // number of materials
int npair; // number of predefined geom pairs
int nexclude; // number of excluded geom pairs
int neq; // number of equality constraints
int ntendon; // number of tendons
int nwrap; // number of wrap objects in all tendon paths
int nsensor; // number of sensors
int nnumeric; // number of numeric custom fields
int nnumericdata; // number of mjtNums in all numeric fields
int ntext; // number of text custom fields
int ntextdata; // number of mjtBytes in all text fields
int ntuple; // number of tuple custom fields
int ntupledata; // number of objects in all tuple fields
int nkey; // number of keyframes
int nmocap; // number of mocap bodies
int nplugin; // number of plugin instances
int npluginattr; // number of chars in all plugin config attributes
int nuser_body; // number of mjtNums in body_user
int nuser_jnt; // number of mjtNums in jnt_user
int nuser_geom; // number of mjtNums in geom_user
int nuser_site; // number of mjtNums in site_user
int nuser_cam; // number of mjtNums in cam_user
int nuser_tendon; // number of mjtNums in tendon_user
int nuser_actuator; // number of mjtNums in actuator_user
int nuser_sensor; // number of mjtNums in sensor_user
int nnames; // number of chars in all names
int npaths; // number of chars in all paths
// sizes set after mjModel construction
int nnames_map; // number of slots in the names hash map
int nM; // number of non-zeros in sparse inertia matrix
int nB; // number of non-zeros in sparse body-dof matrix
int nC; // number of non-zeros in sparse reduced dof-dof matrix
int nD; // number of non-zeros in sparse dof-dof matrix
int nJmom; // number of non-zeros in sparse actuator_moment matrix
int ntree; // number of kinematic trees under world body
int ngravcomp; // number of bodies with nonzero gravcomp
int nemax; // number of potential equality-constraint rows
int njmax; // number of available rows in constraint Jacobian (legacy)
int nconmax; // number of potential contacts in contact list (legacy)
int nuserdata; // number of mjtNums reserved for the user
int nsensordata; // number of mjtNums in sensor data vector
int npluginstate; // number of mjtNums in plugin state vector
size_t narena; // number of bytes in the mjData arena (inclusive of stack)
size_t nbuffer; // number of bytes in buffer
// ------------------------------- options and statistics
mjOption opt; // physics options
mjVisual vis; // visualization options
mjStatistic stat; // model statistics
// ------------------------------- buffers
// main buffer
void* buffer; // main buffer; all pointers point in it (nbuffer)
// default generalized coordinates
mjtNum* qpos0; // qpos values at default pose (nq x 1)
mjtNum* qpos_spring; // reference pose for springs (nq x 1)
// bodies
int* body_parentid; // id of body's parent (nbody x 1)
int* body_rootid; // id of root above body (nbody x 1)
int* body_weldid; // id of body that this body is welded to (nbody x 1)
int* body_mocapid; // id of mocap data; -1: none (nbody x 1)
int* body_jntnum; // number of joints for this body (nbody x 1)
int* body_jntadr; // start addr of joints; -1: no joints (nbody x 1)
int* body_dofnum; // number of motion degrees of freedom (nbody x 1)
int* body_dofadr; // start addr of dofs; -1: no dofs (nbody x 1)
int* body_treeid; // id of body's kinematic tree; -1: static (nbody x 1)
int* body_geomnum; // number of geoms (nbody x 1)
int* body_geomadr; // start addr of geoms; -1: no geoms (nbody x 1)
mjtByte* body_simple; // 1: diag M; 2: diag M, sliders only (nbody x 1)
mjtByte* body_sameframe; // same frame as inertia (mjtSameframe) (nbody x 1)
mjtNum* body_pos; // position offset rel. to parent body (nbody x 3)
mjtNum* body_quat; // orientation offset rel. to parent body (nbody x 4)
mjtNum* body_ipos; // local position of center of mass (nbody x 3)
mjtNum* body_iquat; // local orientation of inertia ellipsoid (nbody x 4)
mjtNum* body_mass; // mass (nbody x 1)
mjtNum* body_subtreemass; // mass of subtree starting at this body (nbody x 1)
mjtNum* body_inertia; // diagonal inertia in ipos/iquat frame (nbody x 3)
mjtNum* body_invweight0; // mean inv inert in qpos0 (trn, rot) (nbody x 2)
mjtNum* body_gravcomp; // antigravity force, units of body weight (nbody x 1)
mjtNum* body_margin; // MAX over all geom margins (nbody x 1)
mjtNum* body_user; // user data (nbody x nuser_body)
int* body_plugin; // plugin instance id; -1: not in use (nbody x 1)
int* body_contype; // OR over all geom contypes (nbody x 1)
int* body_conaffinity; // OR over all geom conaffinities (nbody x 1)
int* body_bvhadr; // address of bvh root (nbody x 1)
int* body_bvhnum; // number of bounding volumes (nbody x 1)
// bounding volume hierarchy
int* bvh_depth; // depth in the bounding volume hierarchy (nbvh x 1)
int* bvh_child; // left and right children in tree (nbvh x 2)
int* bvh_nodeid; // geom or elem id of node; -1: non-leaf (nbvh x 1)
mjtNum* bvh_aabb; // local bounding box (center, size) (nbvhstatic x 6)
// octree spatial partitioning
int* oct_depth; // depth in the octree (noct x 1)
int* oct_child; // children of octree node (noct x 8)
mjtNum* oct_aabb; // octree node bounding box (center, size) (noct x 6)
mjtNum* oct_coeff; // octree interpolation coefficients (noct x 8)
// joints
int* jnt_type; // type of joint (mjtJoint) (njnt x 1)
int* jnt_qposadr; // start addr in 'qpos' for joint's data (njnt x 1)
int* jnt_dofadr; // start addr in 'qvel' for joint's data (njnt x 1)
int* jnt_bodyid; // id of joint's body (njnt x 1)
int* jnt_group; // group for visibility (njnt x 1)
mjtByte* jnt_limited; // does joint have limits (njnt x 1)
mjtByte* jnt_actfrclimited; // does joint have actuator force limits (njnt x 1)
mjtByte* jnt_actgravcomp; // is gravcomp force applied via actuators (njnt x 1)
mjtNum* jnt_solref; // constraint solver reference: limit (njnt x mjNREF)
mjtNum* jnt_solimp; // constraint solver impedance: limit (njnt x mjNIMP)
mjtNum* jnt_pos; // local anchor position (njnt x 3)
mjtNum* jnt_axis; // local joint axis (njnt x 3)
mjtNum* jnt_stiffness; // stiffness coefficient (njnt x 1)
mjtNum* jnt_range; // joint limits (njnt x 2)
mjtNum* jnt_actfrcrange; // range of total actuator force (njnt x 2)
mjtNum* jnt_margin; // min distance for limit detection (njnt x 1)
mjtNum* jnt_user; // user data (njnt x nuser_jnt)
// dofs
int* dof_bodyid; // id of dof's body (nv x 1)
int* dof_jntid; // id of dof's joint (nv x 1)
int* dof_parentid; // id of dof's parent; -1: none (nv x 1)
int* dof_treeid; // id of dof's kinematic tree (nv x 1)
int* dof_Madr; // dof address in M-diagonal (nv x 1)
int* dof_simplenum; // number of consecutive simple dofs (nv x 1)
mjtNum* dof_solref; // constraint solver reference:frictionloss (nv x mjNREF)
mjtNum* dof_solimp; // constraint solver impedance:frictionloss (nv x mjNIMP)
mjtNum* dof_frictionloss; // dof friction loss (nv x 1)
mjtNum* dof_armature; // dof armature inertia/mass (nv x 1)
mjtNum* dof_damping; // damping coefficient (nv x 1)
mjtNum* dof_invweight0; // diag. inverse inertia in qpos0 (nv x 1)
mjtNum* dof_M0; // diag. inertia in qpos0 (nv x 1)
// geoms
int* geom_type; // geometric type (mjtGeom) (ngeom x 1)
int* geom_contype; // geom contact type (ngeom x 1)
int* geom_conaffinity; // geom contact affinity (ngeom x 1)
int* geom_condim; // contact dimensionality (1, 3, 4, 6) (ngeom x 1)
int* geom_bodyid; // id of geom's body (ngeom x 1)
int* geom_dataid; // id of geom's mesh/hfield; -1: none (ngeom x 1)
int* geom_matid; // material id for rendering; -1: none (ngeom x 1)
int* geom_group; // group for visibility (ngeom x 1)
int* geom_priority; // geom contact priority (ngeom x 1)
int* geom_plugin; // plugin instance id; -1: not in use (ngeom x 1)
mjtByte* geom_sameframe; // same frame as body (mjtSameframe) (ngeom x 1)
mjtNum* geom_solmix; // mixing coef for solref/imp in geom pair (ngeom x 1)
mjtNum* geom_solref; // constraint solver reference: contact (ngeom x mjNREF)
mjtNum* geom_solimp; // constraint solver impedance: contact (ngeom x mjNIMP)
mjtNum* geom_size; // geom-specific size parameters (ngeom x 3)
mjtNum* geom_aabb; // bounding box, (center, size) (ngeom x 6)
mjtNum* geom_rbound; // radius of bounding sphere (ngeom x 1)
mjtNum* geom_pos; // local position offset rel. to body (ngeom x 3)
mjtNum* geom_quat; // local orientation offset rel. to body (ngeom x 4)
mjtNum* geom_friction; // friction for (slide, spin, roll) (ngeom x 3)
mjtNum* geom_margin; // detect contact if dist<margin (ngeom x 1)
mjtNum* geom_gap; // include in solver if dist<margin-gap (ngeom x 1)
mjtNum* geom_fluid; // fluid interaction parameters (ngeom x mjNFLUID)
mjtNum* geom_user; // user data (ngeom x nuser_geom)
float* geom_rgba; // rgba when material is omitted (ngeom x 4)
// sites
int* site_type; // geom type for rendering (mjtGeom) (nsite x 1)
int* site_bodyid; // id of site's body (nsite x 1)
int* site_matid; // material id for rendering; -1: none (nsite x 1)
int* site_group; // group for visibility (nsite x 1)
mjtByte* site_sameframe; // same frame as body (mjtSameframe) (nsite x 1)
mjtNum* site_size; // geom size for rendering (nsite x 3)
mjtNum* site_pos; // local position offset rel. to body (nsite x 3)
mjtNum* site_quat; // local orientation offset rel. to body (nsite x 4)
mjtNum* site_user; // user data (nsite x nuser_site)
float* site_rgba; // rgba when material is omitted (nsite x 4)
// cameras
int* cam_mode; // camera tracking mode (mjtCamLight) (ncam x 1)
int* cam_bodyid; // id of camera's body (ncam x 1)
int* cam_targetbodyid; // id of targeted body; -1: none (ncam x 1)
mjtNum* cam_pos; // position rel. to body frame (ncam x 3)
mjtNum* cam_quat; // orientation rel. to body frame (ncam x 4)
mjtNum* cam_poscom0; // global position rel. to sub-com in qpos0 (ncam x 3)
mjtNum* cam_pos0; // global position rel. to body in qpos0 (ncam x 3)
mjtNum* cam_mat0; // global orientation in qpos0 (ncam x 9)
int* cam_orthographic; // orthographic camera; 0: no, 1: yes (ncam x 1)
mjtNum* cam_fovy; // y field-of-view (ortho ? len : deg) (ncam x 1)
mjtNum* cam_ipd; // inter-pupilary distance (ncam x 1)
int* cam_resolution; // resolution: pixels [width, height] (ncam x 2)
float* cam_sensorsize; // sensor size: length [width, height] (ncam x 2)
float* cam_intrinsic; // [focal length; principal point] (ncam x 4)
mjtNum* cam_user; // user data (ncam x nuser_cam)
// lights
int* light_mode; // light tracking mode (mjtCamLight) (nlight x 1)
int* light_bodyid; // id of light's body (nlight x 1)
int* light_targetbodyid; // id of targeted body; -1: none (nlight x 1)
int* light_type; // spot, directional, etc. (mjtLightType) (nlight x 1)
int* light_texid; // texture id for image lights (nlight x 1)
mjtByte* light_castshadow; // does light cast shadows (nlight x 1)
float* light_bulbradius; // light radius for soft shadows (nlight x 1)
float* light_intensity; // intensity, in candela (nlight x 1)
float* light_range; // range of effectiveness (nlight x 1)
mjtByte* light_active; // is light on (nlight x 1)
mjtNum* light_pos; // position rel. to body frame (nlight x 3)
mjtNum* light_dir; // direction rel. to body frame (nlight x 3)
mjtNum* light_poscom0; // global position rel. to sub-com in qpos0 (nlight x 3)
mjtNum* light_pos0; // global position rel. to body in qpos0 (nlight x 3)
mjtNum* light_dir0; // global direction in qpos0 (nlight x 3)
float* light_attenuation; // OpenGL attenuation (quadratic model) (nlight x 3)
float* light_cutoff; // OpenGL cutoff (nlight x 1)
float* light_exponent; // OpenGL exponent (nlight x 1)
float* light_ambient; // ambient rgb (alpha=1) (nlight x 3)
float* light_diffuse; // diffuse rgb (alpha=1) (nlight x 3)
float* light_specular; // specular rgb (alpha=1) (nlight x 3)
// flexes: contact properties
int* flex_contype; // flex contact type (nflex x 1)
int* flex_conaffinity; // flex contact affinity (nflex x 1)
int* flex_condim; // contact dimensionality (1, 3, 4, 6) (nflex x 1)
int* flex_priority; // flex contact priority (nflex x 1)
mjtNum* flex_solmix; // mix coef for solref/imp in contact pair (nflex x 1)
mjtNum* flex_solref; // constraint solver reference: contact (nflex x mjNREF)
mjtNum* flex_solimp; // constraint solver impedance: contact (nflex x mjNIMP)
mjtNum* flex_friction; // friction for (slide, spin, roll) (nflex x 3)
mjtNum* flex_margin; // detect contact if dist<margin (nflex x 1)
mjtNum* flex_gap; // include in solver if dist<margin-gap (nflex x 1)
mjtByte* flex_internal; // internal flex collision enabled (nflex x 1)
int* flex_selfcollide; // self collision mode (mjtFlexSelf) (nflex x 1)
int* flex_activelayers; // number of active element layers, 3D only (nflex x 1)
// flexes: other properties
int* flex_dim; // 1: lines, 2: triangles, 3: tetrahedra (nflex x 1)
int* flex_matid; // material id for rendering (nflex x 1)
int* flex_group; // group for visibility (nflex x 1)
int* flex_interp; // interpolation (0: vertex, 1: nodes) (nflex x 1)
int* flex_nodeadr; // first node address (nflex x 1)
int* flex_nodenum; // number of nodes (nflex x 1)
int* flex_vertadr; // first vertex address (nflex x 1)
int* flex_vertnum; // number of vertices (nflex x 1)
int* flex_edgeadr; // first edge address (nflex x 1)
int* flex_edgenum; // number of edges (nflex x 1)
int* flex_elemadr; // first element address (nflex x 1)
int* flex_elemnum; // number of elements (nflex x 1)
int* flex_elemdataadr; // first element vertex id address (nflex x 1)
int* flex_elemedgeadr; // first element edge id address (nflex x 1)
int* flex_shellnum; // number of shells (nflex x 1)
int* flex_shelldataadr; // first shell data address (nflex x 1)
int* flex_evpairadr; // first evpair address (nflex x 1)
int* flex_evpairnum; // number of evpairs (nflex x 1)
int* flex_texcoordadr; // address in flex_texcoord; -1: none (nflex x 1)
int* flex_nodebodyid; // node body ids (nflexnode x 1)
int* flex_vertbodyid; // vertex body ids (nflexvert x 1)
int* flex_edge; // edge vertex ids (2 per edge) (nflexedge x 2)
int* flex_edgeflap; // adjacent vertex ids (dim=2 only) (nflexedge x 2)
int* flex_elem; // element vertex ids (dim+1 per elem) (nflexelemdata x 1)
int* flex_elemtexcoord; // element texture coordinates (dim+1) (nflexelemdata x 1)
int* flex_elemedge; // element edge ids (nflexelemedge x 1)
int* flex_elemlayer; // element distance from surface, 3D only (nflexelem x 1)
int* flex_shell; // shell fragment vertex ids (dim per frag) (nflexshelldata x 1)
int* flex_evpair; // (element, vertex) collision pairs (nflexevpair x 2)
mjtNum* flex_vert; // vertex positions in local body frames (nflexvert x 3)
mjtNum* flex_vert0; // vertex positions in qpos0 on [0, 1]^d (nflexvert x 3)
mjtNum* flex_node; // node positions in local body frames (nflexnode x 3)
mjtNum* flex_node0; // Cartesian node positions in qpos0 (nflexnode x 3)
mjtNum* flexedge_length0; // edge lengths in qpos0 (nflexedge x 1)
mjtNum* flexedge_invweight0; // edge inv. weight in qpos0 (nflexedge x 1)
mjtNum* flex_radius; // radius around primitive element (nflex x 1)
mjtNum* flex_stiffness; // finite element stiffness matrix (nflexelem x 21)
mjtNum* flex_bending; // bending stiffness (nflexedge x 16)
mjtNum* flex_damping; // Rayleigh's damping coefficient (nflex x 1)
mjtNum* flex_edgestiffness; // edge stiffness (nflex x 1)
mjtNum* flex_edgedamping; // edge damping (nflex x 1)
mjtByte* flex_edgeequality; // is edge equality constraint defined (nflex x 1)
mjtByte* flex_rigid; // are all verices in the same body (nflex x 1)
mjtByte* flexedge_rigid; // are both edge vertices in same body (nflexedge x 1)
mjtByte* flex_centered; // are all vertex coordinates (0,0,0) (nflex x 1)
mjtByte* flex_flatskin; // render flex skin with flat shading (nflex x 1)
int* flex_bvhadr; // address of bvh root; -1: no bvh (nflex x 1)
int* flex_bvhnum; // number of bounding volumes (nflex x 1)
float* flex_rgba; // rgba when material is omitted (nflex x 4)
float* flex_texcoord; // vertex texture coordinates (nflextexcoord x 2)
// meshes
int* mesh_vertadr; // first vertex address (nmesh x 1)
int* mesh_vertnum; // number of vertices (nmesh x 1)
int* mesh_faceadr; // first face address (nmesh x 1)
int* mesh_facenum; // number of faces (nmesh x 1)
int* mesh_bvhadr; // address of bvh root (nmesh x 1)
int* mesh_bvhnum; // number of bvh (nmesh x 1)
int* mesh_octadr; // address of octree root (nmesh x 1)
int* mesh_octnum; // number of octree nodes (nmesh x 1)
int* mesh_normaladr; // first normal address (nmesh x 1)
int* mesh_normalnum; // number of normals (nmesh x 1)
int* mesh_texcoordadr; // texcoord data address; -1: no texcoord (nmesh x 1)
int* mesh_texcoordnum; // number of texcoord (nmesh x 1)
int* mesh_graphadr; // graph data address; -1: no graph (nmesh x 1)
float* mesh_vert; // vertex positions for all meshes (nmeshvert x 3)
float* mesh_normal; // normals for all meshes (nmeshnormal x 3)
float* mesh_texcoord; // vertex texcoords for all meshes (nmeshtexcoord x 2)
int* mesh_face; // vertex face data (nmeshface x 3)
int* mesh_facenormal; // normal face data (nmeshface x 3)
int* mesh_facetexcoord; // texture face data (nmeshface x 3)
int* mesh_graph; // convex graph data (nmeshgraph x 1)
mjtNum* mesh_scale; // scaling applied to asset vertices (nmesh x 3)
mjtNum* mesh_pos; // translation applied to asset vertices (nmesh x 3)
mjtNum* mesh_quat; // rotation applied to asset vertices (nmesh x 4)
int* mesh_pathadr; // address of asset path for mesh; -1: none (nmesh x 1)
int* mesh_polynum; // number of polygons per mesh (nmesh x 1)
int* mesh_polyadr; // first polygon address per mesh (nmesh x 1)
mjtNum* mesh_polynormal; // all polygon normals (nmeshpoly x 3)
int* mesh_polyvertadr; // polygon vertex start address (nmeshpoly x 1)
int* mesh_polyvertnum; // number of vertices per polygon (nmeshpoly x 1)
int* mesh_polyvert; // all polygon vertices (nmeshpolyvert x 1)
int* mesh_polymapadr; // first polygon address per vertex (nmeshvert x 1)
int* mesh_polymapnum; // number of polygons per vertex (nmeshvert x 1)
int* mesh_polymap; // vertex to polygon map (nmeshpolymap x 1)
// skins
int* skin_matid; // skin material id; -1: none (nskin x 1)
int* skin_group; // group for visibility (nskin x 1)
float* skin_rgba; // skin rgba (nskin x 4)
float* skin_inflate; // inflate skin in normal direction (nskin x 1)
int* skin_vertadr; // first vertex address (nskin x 1)
int* skin_vertnum; // number of vertices (nskin x 1)
int* skin_texcoordadr; // texcoord data address; -1: no texcoord (nskin x 1)
int* skin_faceadr; // first face address (nskin x 1)
int* skin_facenum; // number of faces (nskin x 1)
int* skin_boneadr; // first bone in skin (nskin x 1)
int* skin_bonenum; // number of bones in skin (nskin x 1)
float* skin_vert; // vertex positions for all skin meshes (nskinvert x 3)
float* skin_texcoord; // vertex texcoords for all skin meshes (nskintexvert x 2)
int* skin_face; // triangle faces for all skin meshes (nskinface x 3)
int* skin_bonevertadr; // first vertex in each bone (nskinbone x 1)
int* skin_bonevertnum; // number of vertices in each bone (nskinbone x 1)
float* skin_bonebindpos; // bind pos of each bone (nskinbone x 3)
float* skin_bonebindquat; // bind quat of each bone (nskinbone x 4)
int* skin_bonebodyid; // body id of each bone (nskinbone x 1)
int* skin_bonevertid; // mesh ids of vertices in each bone (nskinbonevert x 1)
float* skin_bonevertweight; // weights of vertices in each bone (nskinbonevert x 1)
int* skin_pathadr; // address of asset path for skin; -1: none (nskin x 1)
// height fields
mjtNum* hfield_size; // (x, y, z_top, z_bottom) (nhfield x 4)
int* hfield_nrow; // number of rows in grid (nhfield x 1)
int* hfield_ncol; // number of columns in grid (nhfield x 1)
int* hfield_adr; // address in hfield_data (nhfield x 1)
float* hfield_data; // elevation data (nhfielddata x 1)
int* hfield_pathadr; // address of hfield asset path; -1: none (nhfield x 1)
// textures
int* tex_type; // texture type (mjtTexture) (ntex x 1)
int* tex_colorspace; // texture colorspace (mjtColorSpace) (ntex x 1)
int* tex_height; // number of rows in texture image (ntex x 1)
int* tex_width; // number of columns in texture image (ntex x 1)
int* tex_nchannel; // number of channels in texture image (ntex x 1)
int* tex_adr; // start address in tex_data (ntex x 1)
mjtByte* tex_data; // pixel values (ntexdata x 1)
int* tex_pathadr; // address of texture asset path; -1: none (ntex x 1)
// materials
int* mat_texid; // indices of textures; -1: none (nmat x mjNTEXROLE)
mjtByte* mat_texuniform; // make texture cube uniform (nmat x 1)
float* mat_texrepeat; // texture repetition for 2d mapping (nmat x 2)
float* mat_emission; // emission (x rgb) (nmat x 1)
float* mat_specular; // specular (x white) (nmat x 1)
float* mat_shininess; // shininess coef (nmat x 1)
float* mat_reflectance; // reflectance (0: disable) (nmat x 1)
float* mat_metallic; // metallic coef (nmat x 1)
float* mat_roughness; // roughness coef (nmat x 1)
float* mat_rgba; // rgba (nmat x 4)
// predefined geom pairs for collision detection; has precedence over exclude
int* pair_dim; // contact dimensionality (npair x 1)
int* pair_geom1; // id of geom1 (npair x 1)
int* pair_geom2; // id of geom2 (npair x 1)
int* pair_signature; // body1 << 16 + body2 (npair x 1)
mjtNum* pair_solref; // solver reference: contact normal (npair x mjNREF)
mjtNum* pair_solreffriction; // solver reference: contact friction (npair x mjNREF)
mjtNum* pair_solimp; // solver impedance: contact (npair x mjNIMP)
mjtNum* pair_margin; // detect contact if dist<margin (npair x 1)
mjtNum* pair_gap; // include in solver if dist<margin-gap (npair x 1)
mjtNum* pair_friction; // tangent1, 2, spin, roll1, 2 (npair x 5)
// excluded body pairs for collision detection
int* exclude_signature; // body1 << 16 + body2 (nexclude x 1)
// equality constraints
int* eq_type; // constraint type (mjtEq) (neq x 1)
int* eq_obj1id; // id of object 1 (neq x 1)
int* eq_obj2id; // id of object 2 (neq x 1)
int* eq_objtype; // type of both objects (mjtObj) (neq x 1)
mjtByte* eq_active0; // initial enable/disable constraint state (neq x 1)
mjtNum* eq_solref; // constraint solver reference (neq x mjNREF)
mjtNum* eq_solimp; // constraint solver impedance (neq x mjNIMP)
mjtNum* eq_data; // numeric data for constraint (neq x mjNEQDATA)
// tendons
int* tendon_adr; // address of first object in tendon's path (ntendon x 1)
int* tendon_num; // number of objects in tendon's path (ntendon x 1)
int* tendon_matid; // material id for rendering (ntendon x 1)
int* tendon_group; // group for visibility (ntendon x 1)
mjtByte* tendon_limited; // does tendon have length limits (ntendon x 1)
mjtByte* tendon_actfrclimited; // does tendon have actuator force limits (ntendon x 1)
mjtNum* tendon_width; // width for rendering (ntendon x 1)
mjtNum* tendon_solref_lim; // constraint solver reference: limit (ntendon x mjNREF)
mjtNum* tendon_solimp_lim; // constraint solver impedance: limit (ntendon x mjNIMP)
mjtNum* tendon_solref_fri; // constraint solver reference: friction (ntendon x mjNREF)
mjtNum* tendon_solimp_fri; // constraint solver impedance: friction (ntendon x mjNIMP)
mjtNum* tendon_range; // tendon length limits (ntendon x 2)
mjtNum* tendon_actfrcrange; // range of total actuator force (ntendon x 2)
mjtNum* tendon_margin; // min distance for limit detection (ntendon x 1)
mjtNum* tendon_stiffness; // stiffness coefficient (ntendon x 1)
mjtNum* tendon_damping; // damping coefficient (ntendon x 1)
mjtNum* tendon_armature; // inertia associated with tendon velocity (ntendon x 1)
mjtNum* tendon_frictionloss; // loss due to friction (ntendon x 1)
mjtNum* tendon_lengthspring; // spring resting length range (ntendon x 2)
mjtNum* tendon_length0; // tendon length in qpos0 (ntendon x 1)
mjtNum* tendon_invweight0; // inv. weight in qpos0 (ntendon x 1)
mjtNum* tendon_user; // user data (ntendon x nuser_tendon)
float* tendon_rgba; // rgba when material is omitted (ntendon x 4)
// list of all wrap objects in tendon paths
int* wrap_type; // wrap object type (mjtWrap) (nwrap x 1)
int* wrap_objid; // object id: geom, site, joint (nwrap x 1)
mjtNum* wrap_prm; // divisor, joint coef, or site id (nwrap x 1)
// actuators
int* actuator_trntype; // transmission type (mjtTrn) (nu x 1)
int* actuator_dyntype; // dynamics type (mjtDyn) (nu x 1)
int* actuator_gaintype; // gain type (mjtGain) (nu x 1)
int* actuator_biastype; // bias type (mjtBias) (nu x 1)
int* actuator_trnid; // transmission id: joint, tendon, site (nu x 2)
int* actuator_actadr; // first activation address; -1: stateless (nu x 1)
int* actuator_actnum; // number of activation variables (nu x 1)
int* actuator_group; // group for visibility (nu x 1)
mjtByte* actuator_ctrllimited; // is control limited (nu x 1)
mjtByte* actuator_forcelimited;// is force limited (nu x 1)
mjtByte* actuator_actlimited; // is activation limited (nu x 1)
mjtNum* actuator_dynprm; // dynamics parameters (nu x mjNDYN)
mjtNum* actuator_gainprm; // gain parameters (nu x mjNGAIN)
mjtNum* actuator_biasprm; // bias parameters (nu x mjNBIAS)
mjtByte* actuator_actearly; // step activation before force (nu x 1)
mjtNum* actuator_ctrlrange; // range of controls (nu x 2)
mjtNum* actuator_forcerange; // range of forces (nu x 2)
mjtNum* actuator_actrange; // range of activations (nu x 2)
mjtNum* actuator_gear; // scale length and transmitted force (nu x 6)
mjtNum* actuator_cranklength; // crank length for slider-crank (nu x 1)
mjtNum* actuator_acc0; // acceleration from unit force in qpos0 (nu x 1)
mjtNum* actuator_length0; // actuator length in qpos0 (nu x 1)
mjtNum* actuator_lengthrange; // feasible actuator length range (nu x 2)
mjtNum* actuator_user; // user data (nu x nuser_actuator)
int* actuator_plugin; // plugin instance id; -1: not a plugin (nu x 1)
// sensors
int* sensor_type; // sensor type (mjtSensor) (nsensor x 1)
int* sensor_datatype; // numeric data type (mjtDataType) (nsensor x 1)
int* sensor_needstage; // required compute stage (mjtStage) (nsensor x 1)
int* sensor_objtype; // type of sensorized object (mjtObj) (nsensor x 1)
int* sensor_objid; // id of sensorized object (nsensor x 1)
int* sensor_reftype; // type of reference frame (mjtObj) (nsensor x 1)
int* sensor_refid; // id of reference frame; -1: global frame (nsensor x 1)
int* sensor_intprm; // sensor parameters (nsensor x mjNSENS)
int* sensor_dim; // number of scalar outputs (nsensor x 1)
int* sensor_adr; // address in sensor array (nsensor x 1)
mjtNum* sensor_cutoff; // cutoff for real and positive; 0: ignore (nsensor x 1)
mjtNum* sensor_noise; // noise standard deviation (nsensor x 1)
mjtNum* sensor_user; // user data (nsensor x nuser_sensor)
int* sensor_plugin; // plugin instance id; -1: not a plugin (nsensor x 1)
// plugin instances
int* plugin; // globally registered plugin slot number (nplugin x 1)
int* plugin_stateadr; // address in the plugin state array (nplugin x 1)
int* plugin_statenum; // number of states in the plugin instance (nplugin x 1)
char* plugin_attr; // config attributes of plugin instances (npluginattr x 1)
int* plugin_attradr; // address to each instance's config attrib (nplugin x 1)
// custom numeric fields
int* numeric_adr; // address of field in numeric_data (nnumeric x 1)
int* numeric_size; // size of numeric field (nnumeric x 1)
mjtNum* numeric_data; // array of all numeric fields (nnumericdata x 1)
// custom text fields
int* text_adr; // address of text in text_data (ntext x 1)
int* text_size; // size of text field (strlen+1) (ntext x 1)
char* text_data; // array of all text fields (0-terminated) (ntextdata x 1)
// custom tuple fields
int* tuple_adr; // address of text in text_data (ntuple x 1)
int* tuple_size; // number of objects in tuple (ntuple x 1)
int* tuple_objtype; // array of object types in all tuples (ntupledata x 1)
int* tuple_objid; // array of object ids in all tuples (ntupledata x 1)
mjtNum* tuple_objprm; // array of object params in all tuples (ntupledata x 1)
// keyframes
mjtNum* key_time; // key time (nkey x 1)
mjtNum* key_qpos; // key position (nkey x nq)
mjtNum* key_qvel; // key velocity (nkey x nv)
mjtNum* key_act; // key activation (nkey x na)
mjtNum* key_mpos; // key mocap position (nkey x nmocap*3)
mjtNum* key_mquat; // key mocap quaternion (nkey x nmocap*4)
mjtNum* key_ctrl; // key control (nkey x nu)
// names
int* name_bodyadr; // body name pointers (nbody x 1)
int* name_jntadr; // joint name pointers (njnt x 1)
int* name_geomadr; // geom name pointers (ngeom x 1)
int* name_siteadr; // site name pointers (nsite x 1)
int* name_camadr; // camera name pointers (ncam x 1)
int* name_lightadr; // light name pointers (nlight x 1)
int* name_flexadr; // flex name pointers (nflex x 1)
int* name_meshadr; // mesh name pointers (nmesh x 1)
int* name_skinadr; // skin name pointers (nskin x 1)
int* name_hfieldadr; // hfield name pointers (nhfield x 1)
int* name_texadr; // texture name pointers (ntex x 1)
int* name_matadr; // material name pointers (nmat x 1)
int* name_pairadr; // geom pair name pointers (npair x 1)
int* name_excludeadr; // exclude name pointers (nexclude x 1)
int* name_eqadr; // equality constraint name pointers (neq x 1)
int* name_tendonadr; // tendon name pointers (ntendon x 1)
int* name_actuatoradr; // actuator name pointers (nu x 1)
int* name_sensoradr; // sensor name pointers (nsensor x 1)
int* name_numericadr; // numeric name pointers (nnumeric x 1)
int* name_textadr; // text name pointers (ntext x 1)
int* name_tupleadr; // tuple name pointers (ntuple x 1)
int* name_keyadr; // keyframe name pointers (nkey x 1)
int* name_pluginadr; // plugin instance name pointers (nplugin x 1)
char* names; // names of all objects, 0-terminated (nnames x 1)
int* names_map; // internal hash map of names (nnames_map x 1)
// paths
char* paths; // paths to assets, 0-terminated (npaths x 1)
// compilation signature
uint64_t signature; // also held by the mjSpec that compiled this model
};
typedef struct mjModel_ mjModel;
struct mjResource_ {
char* name; // name of resource (filename, etc)
void* data; // opaque data pointer
char timestamp[512]; // timestamp of the resource
const struct mjpResourceProvider* provider; // pointer to the provider
};
typedef struct mjResource_ mjResource;
struct mjpResourceProvider {
const char* prefix; // prefix for match against a resource name
mjfOpenResource open; // opening callback
mjfReadResource read; // reading callback
mjfCloseResource close; // closing callback
mjfGetResourceDir getdir; // get directory callback (optional)
mjfResourceModified modified; // resource modified callback (optional)
void* data; // opaque data pointer (resource invariant)
};
typedef struct mjpResourceProvider mjpResourceProvider;
typedef enum mjtPluginCapabilityBit_ {
mjPLUGIN_ACTUATOR = 1<<0, // actuator forces
mjPLUGIN_SENSOR = 1<<1, // sensor measurements
mjPLUGIN_PASSIVE = 1<<2, // passive forces
mjPLUGIN_SDF = 1<<3, // signed distance fields
} mjtPluginCapabilityBit;
struct mjpPlugin_ {
const char* name; // globally unique name identifying the plugin
int nattribute; // number of configuration attributes
const char* const* attributes; // name of configuration attributes
int capabilityflags; // plugin capabilities: bitfield of mjtPluginCapabilityBit
int needstage; // sensor computation stage (mjtStage)
// number of mjtNums needed to store the state of a plugin instance (required)
int (*nstate)(const mjModel* m, int instance);
// dimension of the specified sensor's output (required only for sensor plugins)
int (*nsensordata)(const mjModel* m, int instance, int sensor_id);
// called when a new mjData is being created (required), returns 0 on success or -1 on failure
int (*init)(const mjModel* m, mjData* d, int instance);
// called when an mjData is being freed (optional)
void (*destroy)(mjData* d, int instance);
// called when an mjData is being copied (optional)
void (*copy)(mjData* dest, const mjModel* m, const mjData* src, int instance);
// called when an mjData is being reset (required)
void (*reset)(const mjModel* m, mjtNum* plugin_state, void* plugin_data, int instance);
// called when the plugin needs to update its outputs (required)
void (*compute)(const mjModel* m, mjData* d, int instance, int capability_bit);
// called when time integration occurs (optional)
void (*advance)(const mjModel* m, mjData* d, int instance);
// called by mjv_updateScene (optional)
void (*visualize)(const mjModel*m, mjData* d, const mjvOption* opt, mjvScene* scn, int instance);
// methods specific to actuators (optional)
// updates the actuator plugin's entries in act_dot
// called after native act_dot is computed and before the compute callback
void (*actuator_act_dot)(const mjModel* m, mjData* d, int instance);
// methods specific to signed distance fields (optional)
// signed distance from the surface
mjtNum (*sdf_distance)(const mjtNum point[3], const mjData* d, int instance);
// gradient of distance with respect to local coordinates
void (*sdf_gradient)(mjtNum gradient[3], const mjtNum point[3], const mjData* d, int instance);
// called during compilation for marching cubes
mjtNum (*sdf_staticdistance)(const mjtNum point[3], const mjtNum* attributes);
// convert attributes and provide defaults if not present
void (*sdf_attribute)(mjtNum attribute[], const char* name[], const char* value[]);
// bounding box of implicit surface
void (*sdf_aabb)(mjtNum aabb[6], const mjtNum* attributes);
};
typedef struct mjpPlugin_ mjpPlugin;
struct mjSDF_ {
const mjpPlugin** plugin;
int* id;
mjtSDFType type;
mjtNum* relpos;
mjtNum* relmat;
mjtGeom* geomtype;
};
typedef struct mjSDF_ mjSDF;
typedef enum mjtGridPos_ { // grid position for overlay
mjGRID_TOPLEFT = 0, // top left
mjGRID_TOPRIGHT, // top right
mjGRID_BOTTOMLEFT, // bottom left
mjGRID_BOTTOMRIGHT, // bottom right
mjGRID_TOP, // top center
mjGRID_BOTTOM, // bottom center
mjGRID_LEFT, // left center
mjGRID_RIGHT // right center
} mjtGridPos;
typedef enum mjtFramebuffer_ { // OpenGL framebuffer option
mjFB_WINDOW = 0, // default/window buffer
mjFB_OFFSCREEN // offscreen buffer
} mjtFramebuffer;
typedef enum mjtDepthMap_ { // depth mapping for `mjr_readPixels`
mjDEPTH_ZERONEAR = 0, // standard depth map; 0: znear, 1: zfar
mjDEPTH_ZEROFAR = 1 // reversed depth map; 1: znear, 0: zfar
} mjtDepthMap;
typedef enum mjtFontScale_ { // font scale, used at context creation
mjFONTSCALE_50 = 50, // 50% scale, suitable for low-res rendering
mjFONTSCALE_100 = 100, // normal scale, suitable in the absence of DPI scaling
mjFONTSCALE_150 = 150, // 150% scale
mjFONTSCALE_200 = 200, // 200% scale
mjFONTSCALE_250 = 250, // 250% scale
mjFONTSCALE_300 = 300 // 300% scale
} mjtFontScale;
typedef enum mjtFont_ { // font type, used at each text operation
mjFONT_NORMAL = 0, // normal font
mjFONT_SHADOW, // normal font with shadow (for higher contrast)
mjFONT_BIG // big font (for user alerts)
} mjtFont;
struct mjrRect_ { // OpenGL rectangle
int left; // left (usually 0)
int bottom; // bottom (usually 0)
int width; // width (usually buffer width)
int height; // height (usually buffer height)
};
typedef struct mjrRect_ mjrRect;
struct mjrContext_ { // custom OpenGL context
// parameters copied from mjVisual
float lineWidth; // line width for wireframe rendering
float shadowClip; // clipping radius for directional lights
float shadowScale; // fraction of light cutoff for spot lights
float fogStart; // fog start = stat.extent * vis.map.fogstart
float fogEnd; // fog end = stat.extent * vis.map.fogend
float fogRGBA[4]; // fog rgba
int shadowSize; // size of shadow map texture
int offWidth; // width of offscreen buffer
int offHeight; // height of offscreen buffer
int offSamples; // number of offscreen buffer multisamples
// parameters specified at creation
int fontScale; // font scale
int auxWidth[mjNAUX]; // auxiliary buffer width
int auxHeight[mjNAUX]; // auxiliary buffer height
int auxSamples[mjNAUX]; // auxiliary buffer multisamples
// offscreen rendering objects
unsigned int offFBO; // offscreen framebuffer object
unsigned int offFBO_r; // offscreen framebuffer for resolving multisamples
unsigned int offColor; // offscreen color buffer
unsigned int offColor_r; // offscreen color buffer for resolving multisamples
unsigned int offDepthStencil; // offscreen depth and stencil buffer
unsigned int offDepthStencil_r; // offscreen depth and stencil buffer for multisamples
// shadow rendering objects
unsigned int shadowFBO; // shadow map framebuffer object
unsigned int shadowTex; // shadow map texture
// auxiliary buffers
unsigned int auxFBO[mjNAUX]; // auxiliary framebuffer object
unsigned int auxFBO_r[mjNAUX]; // auxiliary framebuffer object for resolving
unsigned int auxColor[mjNAUX]; // auxiliary color buffer
unsigned int auxColor_r[mjNAUX]; // auxiliary color buffer for resolving
// materials with textures
int mat_texid[mjMAXMATERIAL*mjNTEXROLE]; // material texture ids (-1: no texture)
int mat_texuniform[mjMAXMATERIAL]; // uniform cube mapping
float mat_texrepeat[mjMAXMATERIAL*2]; // texture repetition for 2d mapping
// texture objects and info
int ntexture; // number of allocated textures
int textureType[mjMAXTEXTURE]; // type of texture (mjtTexture) (ntexture)
unsigned int texture[mjMAXTEXTURE]; // texture names
// displaylist starting positions
unsigned int basePlane; // all planes from model
unsigned int baseMesh; // all meshes from model
unsigned int baseHField; // all height fields from model
unsigned int baseBuiltin; // all builtin geoms, with quality from model
unsigned int baseFontNormal; // normal font
unsigned int baseFontShadow; // shadow font
unsigned int baseFontBig; // big font
// displaylist ranges
int rangePlane; // all planes from model
int rangeMesh; // all meshes from model
int rangeHField; // all hfields from model
int rangeBuiltin; // all builtin geoms, with quality from model
int rangeFont; // all characters in font
// skin VBOs
int nskin; // number of skins
unsigned int* skinvertVBO; // skin vertex position VBOs (nskin)
unsigned int* skinnormalVBO; // skin vertex normal VBOs (nskin)
unsigned int* skintexcoordVBO; // skin vertex texture coordinate VBOs (nskin)
unsigned int* skinfaceVBO; // skin face index VBOs (nskin)
// character info
int charWidth[127]; // character widths: normal and shadow
int charWidthBig[127]; // chacarter widths: big
int charHeight; // character heights: normal and shadow
int charHeightBig; // character heights: big
// capabilities
int glInitialized; // is OpenGL initialized
int windowAvailable; // is default/window framebuffer available
int windowSamples; // number of samples for default/window framebuffer
int windowStereo; // is stereo available for default/window framebuffer
int windowDoublebuffer; // is default/window framebuffer double buffered
// framebuffer
int currentBuffer; // currently active framebuffer: mjFB_WINDOW or mjFB_OFFSCREEN
// pixel output format
int readPixelFormat; // default color pixel format for mjr_readPixels
// depth output format
int readDepthMap; // depth mapping: mjDEPTH_ZERONEAR or mjDEPTH_ZEROFAR
};
typedef struct mjrContext_ mjrContext;
typedef enum mjtGeomInertia_ { // type of inertia inference
mjINERTIA_VOLUME = 0, // mass distributed in the volume
mjINERTIA_SHELL, // mass distributed on the surface
} mjtGeomInertia;
typedef enum mjtMeshInertia_ { // type of mesh inertia
mjMESH_INERTIA_CONVEX = 0, // convex mesh inertia
mjMESH_INERTIA_EXACT, // exact mesh inertia
mjMESH_INERTIA_LEGACY, // legacy mesh inertia
mjMESH_INERTIA_SHELL // shell mesh inertia
} mjtMeshInertia;
typedef enum mjtBuiltin_ { // type of built-in procedural texture
mjBUILTIN_NONE = 0, // no built-in texture
mjBUILTIN_GRADIENT, // gradient: rgb1->rgb2
mjBUILTIN_CHECKER, // checker pattern: rgb1, rgb2
mjBUILTIN_FLAT // 2d: rgb1; cube: rgb1-up, rgb2-side, rgb3-down
} mjtBuiltin;
typedef enum mjtMark_ { // mark type for procedural textures
mjMARK_NONE = 0, // no mark
mjMARK_EDGE, // edges
mjMARK_CROSS, // cross
mjMARK_RANDOM // random dots
} mjtMark;
typedef enum mjtLimited_ { // type of limit specification
mjLIMITED_FALSE = 0, // not limited
mjLIMITED_TRUE, // limited
mjLIMITED_AUTO, // limited inferred from presence of range
} mjtLimited;
typedef enum mjtAlignFree_ { // whether to align free joints with the inertial frame
mjALIGNFREE_FALSE = 0, // don't align
mjALIGNFREE_TRUE, // align
mjALIGNFREE_AUTO, // respect the global compiler flag
} mjtAlignFree;
typedef enum mjtInertiaFromGeom_ { // whether to infer body inertias from child geoms
mjINERTIAFROMGEOM_FALSE = 0, // do not use; inertial element required
mjINERTIAFROMGEOM_TRUE, // always use; overwrite inertial element
mjINERTIAFROMGEOM_AUTO // use only if inertial element is missing
} mjtInertiaFromGeom;
typedef enum mjtOrientation_ { // type of orientation specifier
mjORIENTATION_QUAT = 0, // quaternion
mjORIENTATION_AXISANGLE, // axis and angle
mjORIENTATION_XYAXES, // x and y axes
mjORIENTATION_ZAXIS, // z axis (minimal rotation)
mjORIENTATION_EULER, // Euler angles
} mjtOrientation;
typedef struct mjsElement_ { // element type, do not modify
mjtObj elemtype; // element type
uint64_t signature; // compilation signature
} mjsElement;
typedef struct mjsCompiler_ { // compiler options
mjtByte autolimits; // infer "limited" attribute based on range
double boundmass; // enforce minimum body mass
double boundinertia; // enforce minimum body diagonal inertia
double settotalmass; // rescale masses and inertias; <=0: ignore
mjtByte balanceinertia; // automatically impose A + B >= C rule
mjtByte fitaabb; // meshfit to aabb instead of inertia box
mjtByte degree; // angles in radians or degrees
char eulerseq[3]; // sequence for euler rotations
mjtByte discardvisual; // discard visual geoms in parser
mjtByte usethread; // use multiple threads to speed up compiler
mjtByte fusestatic; // fuse static bodies with parent
int inertiafromgeom; // use geom inertias (mjtInertiaFromGeom)
int inertiagrouprange[2]; // range of geom groups used to compute inertia
mjtByte saveinertial; // save explicit inertial clause for all bodies to XML
int alignfree; // align free joints with inertial frame
mjLROpt LRopt; // options for lengthrange computation
} mjsCompiler;
typedef struct mjSpec_ { // model specification
mjsElement* element; // element type
mjString* modelname; // model name
// compiler data
mjsCompiler compiler; // compiler options
mjtByte strippath; // automatically strip paths from mesh files
mjString* meshdir; // mesh and hfield directory
mjString* texturedir; // texture directory
// engine data
mjOption option; // physics options
mjVisual visual; // visual options
mjStatistic stat; // statistics override (if defined)
// sizes
size_t memory; // number of bytes in arena+stack memory
int nemax; // max number of equality constraints
int nuserdata; // number of mjtNums in userdata
int nuser_body; // number of mjtNums in body_user
int nuser_jnt; // number of mjtNums in jnt_user
int nuser_geom; // number of mjtNums in geom_user
int nuser_site; // number of mjtNums in site_user
int nuser_cam; // number of mjtNums in cam_user
int nuser_tendon; // number of mjtNums in tendon_user
int nuser_actuator; // number of mjtNums in actuator_user
int nuser_sensor; // number of mjtNums in sensor_user
int nkey; // number of keyframes
int njmax; // (deprecated) max number of constraints
int nconmax; // (deprecated) max number of detected contacts
size_t nstack; // (deprecated) number of mjtNums in mjData stack
// global data
mjString* comment; // comment at top of XML
mjString* modelfiledir; // path to model file
// other
mjtByte hasImplicitPluginElem; // already encountered an implicit plugin sensor/actuator
} mjSpec;
typedef struct mjsOrientation_ { // alternative orientation specifiers
mjtOrientation type; // active orientation specifier
double axisangle[4]; // axis and angle
double xyaxes[6]; // x and y axes
double zaxis[3]; // z axis (minimal rotation)
double euler[3]; // Euler angles
} mjsOrientation;
typedef struct mjsPlugin_ { // plugin specification
mjsElement* element; // element type
mjString* name; // instance name
mjString* plugin_name; // plugin name
mjtByte active; // is the plugin active
mjString* info; // message appended to compiler errors
} mjsPlugin;
typedef struct mjsBody_ { // body specification
mjsElement* element; // element type
mjString* childclass; // childclass name
// body frame
double pos[3]; // frame position
double quat[4]; // frame orientation
mjsOrientation alt; // frame alternative orientation
// inertial frame
double mass; // mass
double ipos[3]; // inertial frame position
double iquat[4]; // inertial frame orientation
double inertia[3]; // diagonal inertia (in i-frame)
mjsOrientation ialt; // inertial frame alternative orientation
double fullinertia[6]; // non-axis-aligned inertia matrix
// other
mjtByte mocap; // is this a mocap body
double gravcomp; // gravity compensation
mjDoubleVec* userdata; // user data
mjtByte explicitinertial; // whether to save the body with explicit inertial clause
mjsPlugin plugin; // passive force plugin
mjString* info; // message appended to compiler errors
} mjsBody;
typedef struct mjsFrame_ { // frame specification
mjsElement* element; // element type
mjString* childclass; // childclass name
double pos[3]; // position
double quat[4]; // orientation
mjsOrientation alt; // alternative orientation
mjString* info; // message appended to compiler errors
} mjsFrame;
typedef struct mjsJoint_ { // joint specification
mjsElement* element; // element type
mjtJoint type; // joint type
// kinematics
double pos[3]; // anchor position
double axis[3]; // joint axis
double ref; // value at reference configuration: qpos0
int align; // align free joint with body com (mjtAlignFree)
// stiffness
double stiffness; // stiffness coefficient
double springref; // spring reference value: qpos_spring
double springdamper[2]; // timeconst, dampratio
// limits
int limited; // does joint have limits (mjtLimited)
double range[2]; // joint limits
double margin; // margin value for joint limit detection
mjtNum solref_limit[mjNREF]; // solver reference: joint limits
mjtNum solimp_limit[mjNIMP]; // solver impedance: joint limits
int actfrclimited; // are actuator forces on joint limited (mjtLimited)
double actfrcrange[2]; // actuator force limits
// dof properties
double armature; // armature inertia (mass for slider)
double damping; // damping coefficient
double frictionloss; // friction loss
mjtNum solref_friction[mjNREF]; // solver reference: dof friction
mjtNum solimp_friction[mjNIMP]; // solver impedance: dof friction
// other
int group; // group
mjtByte actgravcomp; // is gravcomp force applied via actuators
mjDoubleVec* userdata; // user data
mjString* info; // message appended to compiler errors
} mjsJoint;
typedef struct mjsGeom_ { // geom specification
mjsElement* element; // element type
mjtGeom type; // geom type
// frame, size
double pos[3]; // position
double quat[4]; // orientation
mjsOrientation alt; // alternative orientation
double fromto[6]; // alternative for capsule, cylinder, box, ellipsoid
double size[3]; // type-specific size
// contact related
int contype; // contact type
int conaffinity; // contact affinity
int condim; // contact dimensionality
int priority; // contact priority
double friction[3]; // one-sided friction coefficients: slide, roll, spin
double solmix; // solver mixing for contact pairs
mjtNum solref[mjNREF]; // solver reference
mjtNum solimp[mjNIMP]; // solver impedance
double margin; // margin for contact detection
double gap; // include in solver if dist < margin-gap
// inertia inference
double mass; // used to compute density
double density; // used to compute mass and inertia from volume or surface
mjtGeomInertia typeinertia; // selects between surface and volume inertia
// fluid forces
mjtNum fluid_ellipsoid; // whether ellipsoid-fluid model is active
mjtNum fluid_coefs[5]; // ellipsoid-fluid interaction coefs
// visual
mjString* material; // name of material
float rgba[4]; // rgba when material is omitted
int group; // group
// other
mjString* hfieldname; // heightfield attached to geom
mjString* meshname; // mesh attached to geom
double fitscale; // scale mesh uniformly
mjDoubleVec* userdata; // user data
mjsPlugin plugin; // sdf plugin
mjString* info; // message appended to compiler errors
} mjsGeom;
typedef struct mjsSite_ { // site specification
mjsElement* element; // element type
// frame, size
double pos[3]; // position
double quat[4]; // orientation
mjsOrientation alt; // alternative orientation
double fromto[6]; // alternative for capsule, cylinder, box, ellipsoid
double size[3]; // geom size
// visual
mjtGeom type; // geom type
mjString* material; // name of material
int group; // group
float rgba[4]; // rgba when material is omitted
// other
mjDoubleVec* userdata; // user data
mjString* info; // message appended to compiler errors
} mjsSite;
typedef struct mjsCamera_ { // camera specification
mjsElement* element; // element type
// extrinsics
double pos[3]; // position
double quat[4]; // orientation
mjsOrientation alt; // alternative orientation
mjtCamLight mode; // tracking mode
mjString* targetbody; // target body for tracking/targeting
// intrinsics
int orthographic; // is camera orthographic
double fovy; // y-field of view
double ipd; // inter-pupilary distance
float intrinsic[4]; // camera intrinsics (length)
float sensor_size[2]; // sensor size (length)
float resolution[2]; // resolution (pixel)
float focal_length[2]; // focal length (length)
float focal_pixel[2]; // focal length (pixel)
float principal_length[2]; // principal point (length)
float principal_pixel[2]; // principal point (pixel)
// other
mjDoubleVec* userdata; // user data
mjString* info; // message appended to compiler errors
} mjsCamera;
typedef struct mjsLight_ { // light specification
mjsElement* element; // element type
// frame
double pos[3]; // position
double dir[3]; // direction
mjtCamLight mode; // tracking mode
mjString* targetbody; // target body for targeting
// intrinsics
mjtByte active; // is light active
mjtLightType type; // type of light
mjString* texture; // texture name for image lights
mjtByte castshadow; // does light cast shadows
float bulbradius; // bulb radius, for soft shadows
float intensity; // intensity, in candelas
float range; // range of effectiveness
float attenuation[3]; // OpenGL attenuation (quadratic model)
float cutoff; // OpenGL cutoff
float exponent; // OpenGL exponent
float ambient[3]; // ambient color
float diffuse[3]; // diffuse color
float specular[3]; // specular color
// other
mjString* info; // message appended to compiler errorsx
} mjsLight;
typedef struct mjsFlex_ { // flex specification
mjsElement* element; // element type
// contact properties
int contype; // contact type
int conaffinity; // contact affinity
int condim; // contact dimensionality
int priority; // contact priority
double friction[3]; // one-sided friction coefficients: slide, roll, spin
double solmix; // solver mixing for contact pairs
mjtNum solref[mjNREF]; // solver reference
mjtNum solimp[mjNIMP]; // solver impedance
double margin; // margin for contact detection
double gap; // include in solver if dist<margin-gap
// other properties
int dim; // element dimensionality
double radius; // radius around primitive element
mjtByte internal; // enable internal collisions
mjtByte flatskin; // render flex skin with flat shading
int selfcollide; // mode for flex self collision
int vertcollide; // mode for vertex collision
int activelayers; // number of active element layers in 3D
int group; // group for visualizatioh
double edgestiffness; // edge stiffness
double edgedamping; // edge damping
float rgba[4]; // rgba when material is omitted
mjString* material; // name of material used for rendering
double young; // Young's modulus
double poisson; // Poisson's ratio
double damping; // Rayleigh's damping
double thickness; // thickness (2D only)
int elastic2d; // 2D passive forces; 0: none, 1: bending, 2: stretching, 3: both
// mesh properties
mjStringVec* nodebody; // node body names
mjStringVec* vertbody; // vertex body names
mjDoubleVec* node; // node positions
mjDoubleVec* vert; // vertex positions
mjIntVec* elem; // element vertex ids
mjFloatVec* texcoord; // vertex texture coordinates
mjIntVec* elemtexcoord; // element texture coordinates
// other
mjString* info; // message appended to compiler errors
} mjsFlex;
typedef struct mjsMesh_ { // mesh specification
mjsElement* element; // element type
mjString* content_type; // content type of file
mjString* file; // mesh file
double refpos[3]; // reference position
double refquat[4]; // reference orientation
double scale[3]; // rescale mesh
mjtMeshInertia inertia; // inertia type (convex, legacy, exact, shell)
mjtByte smoothnormal; // do not exclude large-angle faces from normals
int maxhullvert; // maximum vertex count for the convex hull
mjFloatVec* uservert; // user vertex data
mjFloatVec* usernormal; // user normal data
mjFloatVec* usertexcoord; // user texcoord data
mjIntVec* userface; // user vertex indices
mjIntVec* userfacetexcoord; // user texcoord indices
mjsPlugin plugin; // sdf plugin
mjString* info; // message appended to compiler errors
} mjsMesh;
typedef struct mjsHField_ { // height field specification
mjsElement* element; // element type
mjString* content_type; // content type of file
mjString* file; // file: (nrow, ncol, [elevation data])
double size[4]; // hfield size (ignore referencing geom size)
int nrow; // number of rows
int ncol; // number of columns
mjFloatVec* userdata; // user-provided elevation data
mjString* info; // message appended to compiler errors
} mjsHField;
typedef struct mjsSkin_ { // skin specification
mjsElement* element; // element type
mjString* file; // skin file
mjString* material; // name of material used for rendering
float rgba[4]; // rgba when material is omitted
float inflate; // inflate in normal direction
int group; // group for visualization
// mesh
mjFloatVec* vert; // vertex positions
mjFloatVec* texcoord; // texture coordinates
mjIntVec* face; // faces
// skin
mjStringVec* bodyname; // body names
mjFloatVec* bindpos; // bind pos
mjFloatVec* bindquat; // bind quat
mjIntVecVec* vertid; // vertex ids
mjFloatVecVec* vertweight; // vertex weights
// other
mjString* info; // message appended to compiler errors
} mjsSkin;
typedef struct mjsTexture_ { // texture specification
mjsElement* element; // element type
mjtTexture type; // texture type
mjtColorSpace colorspace; // colorspace
// method 1: builtin
int builtin; // builtin type (mjtBuiltin)
int mark; // mark type (mjtMark)
double rgb1[3]; // first color for builtin
double rgb2[3]; // second color for builtin
double markrgb[3]; // mark color
double random; // probability of random dots
int height; // height in pixels (square for cube and skybox)
int width; // width in pixels
int nchannel; // number of channels
// method 2: single file
mjString* content_type; // content type of file
mjString* file; // png file to load; use for all sides of cube
int gridsize[2]; // size of grid for composite file; (1,1)-repeat
char gridlayout[13]; // row-major: L,R,F,B,U,D for faces; . for unused
// method 3: separate files
mjStringVec* cubefiles; // different file for each side of the cube
// method 4: from buffer read by user
mjByteVec* data; // texture data
// flip options
mjtByte hflip; // horizontal flip
mjtByte vflip; // vertical flip
// other
mjString* info; // message appended to compiler errors
} mjsTexture;
typedef struct mjsMaterial_ { // material specification
mjsElement* element; // element type
mjStringVec* textures; // names of textures (empty: none)
mjtByte texuniform; // make texture cube uniform
float texrepeat[2]; // texture repetition for 2D mapping
float emission; // emission
float specular; // specular
float shininess; // shininess
float reflectance; // reflectance
float metallic; // metallic
float roughness; // roughness
float rgba[4]; // rgba
mjString* info; // message appended to compiler errors
} mjsMaterial;
typedef struct mjsPair_ { // pair specification
mjsElement* element; // element type
mjString* geomname1; // name of geom 1
mjString* geomname2; // name of geom 2
// optional parameters: computed from geoms if not set by user
int condim; // contact dimensionality
mjtNum solref[mjNREF]; // solver reference, normal direction
mjtNum solreffriction[mjNREF]; // solver reference, frictional directions
mjtNum solimp[mjNIMP]; // solver impedance
double margin; // margin for contact detection
double gap; // include in solver if dist<margin-gap
double friction[5]; // full contact friction
mjString* info; // message appended to errors
} mjsPair;
typedef struct mjsExclude_ { // exclude specification
mjsElement* element; // element type
mjString* bodyname1; // name of geom 1
mjString* bodyname2; // name of geom 2
mjString* info; // message appended to errors
} mjsExclude;
typedef struct mjsEquality_ { // equality specification
mjsElement* element; // element type
mjtEq type; // constraint type
double data[mjNEQDATA]; // type-dependent data
mjtByte active; // is equality initially active
mjString* name1; // name of object 1
mjString* name2; // name of object 2
mjtObj objtype; // type of both objects
mjtNum solref[mjNREF]; // solver reference
mjtNum solimp[mjNIMP]; // solver impedance
mjString* info; // message appended to errors
} mjsEquality;
typedef struct mjsTendon_ { // tendon specification
mjsElement* element; // element type
// stiffness, damping, friction, armature
double stiffness; // stiffness coefficient
double springlength[2]; // spring resting length; {-1, -1}: use qpos_spring
double damping; // damping coefficient
double frictionloss; // friction loss
mjtNum solref_friction[mjNREF]; // solver reference: tendon friction
mjtNum solimp_friction[mjNIMP]; // solver impedance: tendon friction
double armature; // inertia associated with tendon velocity
// length range
int limited; // does tendon have limits (mjtLimited)
int actfrclimited; // does tendon have actuator force limits
double range[2]; // length limits
double actfrcrange[2]; // actuator force limits
double margin; // margin value for tendon limit detection
mjtNum solref_limit[mjNREF]; // solver reference: tendon limits
mjtNum solimp_limit[mjNIMP]; // solver impedance: tendon limits
// visual
mjString* material; // name of material for rendering
double width; // width for rendering
float rgba[4]; // rgba when material is omitted
int group; // group
// other
mjDoubleVec* userdata; // user data
mjString* info; // message appended to errors
} mjsTendon;
typedef struct mjsWrap_ { // wrapping object specification
mjsElement* element; // element type
mjString* info; // message appended to errors
} mjsWrap;
typedef struct mjsActuator_ { // actuator specification
mjsElement* element; // element type
// gain, bias
mjtGain gaintype; // gain type
double gainprm[mjNGAIN]; // gain parameters
mjtBias biastype; // bias type
double biasprm[mjNGAIN]; // bias parameters
// activation state
mjtDyn dyntype; // dynamics type
double dynprm[mjNDYN]; // dynamics parameters
int actdim; // number of activation variables
mjtByte actearly; // apply next activations to qfrc
// transmission
mjtTrn trntype; // transmission type
double gear[6]; // length and transmitted force scaling
mjString* target; // name of transmission target
mjString* refsite; // reference site, for site transmission
mjString* slidersite; // site defining cylinder, for slider-crank
double cranklength; // crank length, for slider-crank
double lengthrange[2]; // transmission length range
double inheritrange; // automatic range setting for position and intvelocity
// input/output clamping
int ctrllimited; // are control limits defined (mjtLimited)
double ctrlrange[2]; // control range
int forcelimited; // are force limits defined (mjtLimited)
double forcerange[2]; // force range
int actlimited; // are activation limits defined (mjtLimited)
double actrange[2]; // activation range
// other
int group; // group
mjDoubleVec* userdata; // user data
mjsPlugin plugin; // actuator plugin
mjString* info; // message appended to compiler errors
} mjsActuator;
typedef struct mjsSensor_ { // sensor specification
mjsElement* element; // element type
// sensor definition
mjtSensor type; // type of sensor
mjtObj objtype; // type of sensorized object
mjString* objname; // name of sensorized object
mjtObj reftype; // type of referenced object
mjString* refname; // name of referenced object
int intprm[mjNSENS]; // integer parameters
// user-defined sensors
mjtDataType datatype; // data type for sensor measurement
mjtStage needstage; // compute stage needed to simulate sensor
int dim; // number of scalar outputs
// output post-processing
double cutoff; // cutoff for real and positive datatypes
double noise; // noise stdev
// other
mjDoubleVec* userdata; // user data
mjsPlugin plugin; // sensor plugin
mjString* info; // message appended to compiler errors
} mjsSensor;
typedef struct mjsNumeric_ { // custom numeric field specification
mjsElement* element; // element type
mjDoubleVec* data; // initialization data
int size; // array size, can be bigger than data size
mjString* info; // message appended to compiler errors
} mjsNumeric;
typedef struct mjsText_ { // custom text specification
mjsElement* element; // element type
mjString* data; // text string
mjString* info; // message appended to compiler errors
} mjsText;
typedef struct mjsTuple_ { // tuple specification
mjsElement* element; // element type
mjIntVec* objtype; // object types
mjStringVec* objname; // object names
mjDoubleVec* objprm; // object parameters
mjString* info; // message appended to compiler errors
} mjsTuple;
typedef struct mjsKey_ { // keyframe specification
mjsElement* element; // element type
double time; // time
mjDoubleVec* qpos; // qpos
mjDoubleVec* qvel; // qvel
mjDoubleVec* act; // act
mjDoubleVec* mpos; // mocap pos
mjDoubleVec* mquat; // mocap quat
mjDoubleVec* ctrl; // ctrl
mjString* info; // message appended to compiler errors
} mjsKey;
typedef struct mjsDefault_ { // default specification
mjsElement* element; // element type
mjsJoint* joint; // joint defaults
mjsGeom* geom; // geom defaults
mjsSite* site; // site defaults
mjsCamera* camera; // camera defaults
mjsLight* light; // light defaults
mjsFlex* flex; // flex defaults
mjsMesh* mesh; // mesh defaults
mjsMaterial* material; // material defaults
mjsPair* pair; // pair defaults
mjsEquality* equality; // equality defaults
mjsTendon* tendon; // tendon defaults
mjsActuator* actuator; // actuator defaults
} mjsDefault;
typedef enum mjtTaskStatus_ { // status values for mjTask
mjTASK_NEW = 0, // newly created
mjTASK_QUEUED, // enqueued in a thread pool
mjTASK_COMPLETED // completed execution
} mjtTaskStatus;
struct mjThreadPool_ {
int nworker; // number of workers in the pool
};
typedef struct mjThreadPool_ mjThreadPool;
struct mjTask_ { // a task that can be executed by a thread pool.
mjfTask func; // pointer to the function that implements the task
void* args; // arguments to func
volatile int status; // status of the task
};
typedef struct mjTask_ mjTask;
typedef enum mjtButton_ { // mouse button
mjBUTTON_NONE = 0, // no button
mjBUTTON_LEFT, // left button
mjBUTTON_RIGHT, // right button
mjBUTTON_MIDDLE // middle button
} mjtButton;
typedef enum mjtEvent_ { // mouse and keyboard event type
mjEVENT_NONE = 0, // no event
mjEVENT_MOVE, // mouse move
mjEVENT_PRESS, // mouse button press
mjEVENT_RELEASE, // mouse button release
mjEVENT_SCROLL, // scroll
mjEVENT_KEY, // key press
mjEVENT_RESIZE, // resize
mjEVENT_REDRAW, // redraw
mjEVENT_FILESDROP // files drop
} mjtEvent;
typedef enum mjtItem_ { // UI item type
mjITEM_END = -2, // end of definition list (not an item)
mjITEM_SECTION = -1, // section (not an item)
mjITEM_SEPARATOR = 0, // separator
mjITEM_STATIC, // static text
mjITEM_BUTTON, // button
// the rest have data pointer
mjITEM_CHECKINT, // check box, int value
mjITEM_CHECKBYTE, // check box, mjtByte value
mjITEM_RADIO, // radio group
mjITEM_RADIOLINE, // radio group, single line
mjITEM_SELECT, // selection box
mjITEM_SLIDERINT, // slider, int value
mjITEM_SLIDERNUM, // slider, mjtNum value
mjITEM_EDITINT, // editable array, int values
mjITEM_EDITNUM, // editable array, mjtNum values
mjITEM_EDITFLOAT, // editable array, float values
mjITEM_EDITTXT, // editable text
mjNITEM // number of item types
} mjtItem;
typedef enum mjtSection_ { // UI section state
mjSECT_CLOSED = 0, // closed state (regular section)
mjSECT_OPEN, // open state (regular section)
mjSECT_FIXED // fixed section: always open, no title
} mjtSection;
struct mjuiState_ { // mouse and keyboard state
// constants set by user
int nrect; // number of rectangles used
mjrRect rect[mjMAXUIRECT]; // rectangles (index 0: entire window)
void* userdata; // pointer to user data (for callbacks)
// event type
int type; // (type mjtEvent)
// mouse buttons
int left; // is left button down
int right; // is right button down
int middle; // is middle button down
int doubleclick; // is last press a double click
int button; // which button was pressed (mjtButton)
double buttontime; // time of last button press
// mouse position
double x; // x position
double y; // y position
double dx; // x displacement
double dy; // y displacement
double sx; // x scroll
double sy; // y scroll
// keyboard
int control; // is control down
int shift; // is shift down
int alt; // is alt down
int key; // which key was pressed
double keytime; // time of last key press
// rectangle ownership and dragging
int mouserect; // which rectangle contains mouse
int dragrect; // which rectangle is dragged with mouse
int dragbutton; // which button started drag (mjtButton)
// files dropping (only valid when type == mjEVENT_FILESDROP)
int dropcount; // number of files dropped
const char** droppaths; // paths to files dropped
};
typedef struct mjuiState_ mjuiState;
struct mjuiThemeSpacing_ { // UI visualization theme spacing
int total; // total width
int scroll; // scrollbar width
int label; // label width
int section; // section gap
int cornersect; // corner radius for section
int cornersep; // corner radius for separator
int itemside; // item side gap
int itemmid; // item middle gap
int itemver; // item vertical gap
int texthor; // text horizontal gap
int textver; // text vertical gap
int linescroll; // number of pixels to scroll
int samples; // number of multisamples
};
typedef struct mjuiThemeSpacing_ mjuiThemeSpacing;
struct mjuiThemeColor_ { // UI visualization theme color
float master[3]; // master background
float thumb[3]; // scrollbar thumb
float secttitle[3]; // section title
float secttitle2[3]; // section title: bottom color
float secttitleuncheck[3]; // section title with unchecked box
float secttitleuncheck2[3]; // section title with unchecked box: bottom color
float secttitlecheck[3]; // section title with checked box
float secttitlecheck2[3]; // section title with checked box: bottom color
float sectfont[3]; // section font
float sectsymbol[3]; // section symbol
float sectpane[3]; // section pane
float separator[3]; // separator title
float separator2[3]; // separator title: bottom color
float shortcut[3]; // shortcut background
float fontactive[3]; // font active
float fontinactive[3]; // font inactive
float decorinactive[3]; // decor inactive
float decorinactive2[3]; // inactive slider color 2
float button[3]; // button
float check[3]; // check
float radio[3]; // radio
float select[3]; // select
float select2[3]; // select pane
float slider[3]; // slider
float slider2[3]; // slider color 2
float edit[3]; // edit
float edit2[3]; // edit invalid
float cursor[3]; // edit cursor
};
typedef struct mjuiThemeColor_ mjuiThemeColor;
struct mjuiItemSingle_ { // check and button-related
int modifier; // 0: none, 1: control, 2: shift; 4: alt
int shortcut; // shortcut key; 0: undefined
};
struct mjuiItemMulti_ { // static, radio and select-related
int nelem; // number of elements in group
char name[mjMAXUIMULTI][mjMAXUINAME]; // element names
};
struct mjuiItemSlider_ { // slider-related
double range[2]; // slider range
double divisions; // number of range divisions
};
struct mjuiItemEdit_ { // edit-related
int nelem; // number of elements in list
double range[mjMAXUIEDIT][2]; // element range (min>=max: ignore)
};
struct mjuiItem_ { // UI item
// common properties
int type; // type (mjtItem)
char name[mjMAXUINAME]; // name
int state; // 0: disable, 1: enable, 2+: use predicate
void *pdata; // data pointer (type-specific)
int sectionid; // id of section containing item
int itemid; // id of item within section
int userid; // user-supplied id (for event handling)
// type-specific properties
union {
struct mjuiItemSingle_ single; // check and button
struct mjuiItemMulti_ multi; // static, radio and select
struct mjuiItemSlider_ slider; // slider
struct mjuiItemEdit_ edit; // edit
};
// internal
mjrRect rect; // rectangle occupied by item
int skip; // item skipped due to closed separator
};
typedef struct mjuiItem_ mjuiItem;
struct mjuiSection_ { // UI section
// properties
char name[mjMAXUINAME]; // name
int state; // section state (mjtSection)
int modifier; // 0: none, 1: control, 2: shift; 4: alt
int shortcut; // shortcut key; 0: undefined
int checkbox; // 0: none, 1: unchecked, 2: checked
int nitem; // number of items in use
mjuiItem item[mjMAXUIITEM]; // preallocated array of items
// internal
mjrRect rtitle; // rectangle occupied by title
mjrRect rcontent; // rectangle occupied by content
int lastclick; // last mouse click over this section
};
typedef struct mjuiSection_ mjuiSection;
struct mjUI_ { // entire UI
// constants set by user
mjuiThemeSpacing spacing; // UI theme spacing
mjuiThemeColor color; // UI theme color
mjfItemEnable predicate; // callback to set item state programmatically
void* userdata; // pointer to user data (passed to predicate)
int rectid; // index of this ui rectangle in mjuiState
int auxid; // aux buffer index of this ui
int radiocol; // number of radio columns (0 defaults to 2)
// UI sizes (framebuffer units)
int width; // width
int height; // current height
int maxheight; // height when all sections open
int scroll; // scroll from top of UI
// mouse focus and count
int mousesect; // 0: none, -1: scroll, otherwise 1+section
int mouseitem; // item within section
int mousehelp; // help button down: print shortcuts
int mouseclicks; // number of mouse clicks over UI
int mousesectcheck; // 0: none, otherwise 1+section
// keyboard focus and edit
int editsect; // 0: none, otherwise 1+section
int edititem; // item within section
int editcursor; // cursor position
int editscroll; // horizontal scroll
char edittext[mjMAXUITEXT]; // current text
mjuiItem* editchanged; // pointer to changed edit in last mjui_event
// sections
int nsect; // number of sections in use
mjuiSection sect[mjMAXUISECT]; // preallocated array of sections
};
typedef struct mjUI_ mjUI;
struct mjuiDef_ { // table passed to mjui_add()
int type; // type (mjtItem); -1: section
char name[mjMAXUINAME]; // name
int state; // state
void* pdata; // pointer to data
char other[mjMAXUITEXT]; // string with type-specific properties
int otherint; // int with type-specific properties
};
typedef struct mjuiDef_ mjuiDef;
typedef enum mjtCatBit_ { // bitflags for mjvGeom category
mjCAT_STATIC = 1, // model elements in body 0
mjCAT_DYNAMIC = 2, // model elements in all other bodies
mjCAT_DECOR = 4, // decorative geoms
mjCAT_ALL = 7 // select all categories
} mjtCatBit;
typedef enum mjtMouse_ { // mouse interaction mode
mjMOUSE_NONE = 0, // no action
mjMOUSE_ROTATE_V, // rotate, vertical plane
mjMOUSE_ROTATE_H, // rotate, horizontal plane
mjMOUSE_MOVE_V, // move, vertical plane
mjMOUSE_MOVE_H, // move, horizontal plane
mjMOUSE_ZOOM, // zoom
mjMOUSE_SELECT // selection
} mjtMouse;
typedef enum mjtPertBit_ { // mouse perturbations
mjPERT_TRANSLATE = 1, // translation
mjPERT_ROTATE = 2 // rotation
} mjtPertBit;
typedef enum mjtCamera_ { // abstract camera type
mjCAMERA_FREE = 0, // free camera
mjCAMERA_TRACKING, // tracking camera; uses trackbodyid
mjCAMERA_FIXED, // fixed camera; uses fixedcamid
mjCAMERA_USER // user is responsible for setting OpenGL camera
} mjtCamera;
typedef enum mjtLabel_ { // object labeling
mjLABEL_NONE = 0, // nothing
mjLABEL_BODY, // body labels
mjLABEL_JOINT, // joint labels
mjLABEL_GEOM, // geom labels
mjLABEL_SITE, // site labels
mjLABEL_CAMERA, // camera labels
mjLABEL_LIGHT, // light labels
mjLABEL_TENDON, // tendon labels
mjLABEL_ACTUATOR, // actuator labels
mjLABEL_CONSTRAINT, // constraint labels
mjLABEL_FLEX, // flex labels
mjLABEL_SKIN, // skin labels
mjLABEL_SELECTION, // selected object
mjLABEL_SELPNT, // coordinates of selection point
mjLABEL_CONTACTPOINT, // contact information
mjLABEL_CONTACTFORCE, // magnitude of contact force
mjLABEL_ISLAND, // id of island
mjNLABEL // number of label types
} mjtLabel;
typedef enum mjtFrame_ { // frame visualization
mjFRAME_NONE = 0, // no frames
mjFRAME_BODY, // body frames
mjFRAME_GEOM, // geom frames
mjFRAME_SITE, // site frames
mjFRAME_CAMERA, // camera frames
mjFRAME_LIGHT, // light frames
mjFRAME_CONTACT, // contact frames
mjFRAME_WORLD, // world frame
mjNFRAME // number of visualization frames
} mjtFrame;
typedef enum mjtVisFlag_ { // flags enabling model element visualization
mjVIS_CONVEXHULL = 0, // mesh convex hull
mjVIS_TEXTURE, // textures
mjVIS_JOINT, // joints
mjVIS_CAMERA, // cameras
mjVIS_ACTUATOR, // actuators
mjVIS_ACTIVATION, // activations
mjVIS_LIGHT, // lights
mjVIS_TENDON, // tendons
mjVIS_RANGEFINDER, // rangefinder sensors
mjVIS_CONSTRAINT, // point constraints
mjVIS_INERTIA, // equivalent inertia boxes
mjVIS_SCLINERTIA, // scale equivalent inertia boxes with mass
mjVIS_PERTFORCE, // perturbation force
mjVIS_PERTOBJ, // perturbation object
mjVIS_CONTACTPOINT, // contact points
mjVIS_ISLAND, // constraint islands
mjVIS_CONTACTFORCE, // contact force
mjVIS_CONTACTSPLIT, // split contact force into normal and tangent
mjVIS_TRANSPARENT, // make dynamic geoms more transparent
mjVIS_AUTOCONNECT, // auto connect joints and body coms
mjVIS_COM, // center of mass
mjVIS_SELECT, // selection point
mjVIS_STATIC, // static bodies
mjVIS_SKIN, // skin
mjVIS_FLEXVERT, // flex vertices
mjVIS_FLEXEDGE, // flex edges
mjVIS_FLEXFACE, // flex element faces
mjVIS_FLEXSKIN, // flex smooth skin (disables the rest)
mjVIS_BODYBVH, // body bounding volume hierarchy
mjVIS_FLEXBVH, // flex bounding volume hierarchy
mjVIS_MESHBVH, // mesh bounding volume hierarchy
mjVIS_SDFITER, // iterations of SDF gradient descent
mjNVISFLAG // number of visualization flags
} mjtVisFlag;
typedef enum mjtRndFlag_ { // flags enabling rendering effects
mjRND_SHADOW = 0, // shadows
mjRND_WIREFRAME, // wireframe
mjRND_REFLECTION, // reflections
mjRND_ADDITIVE, // additive transparency
mjRND_SKYBOX, // skybox
mjRND_FOG, // fog
mjRND_HAZE, // haze
mjRND_SEGMENT, // segmentation with random color
mjRND_IDCOLOR, // segmentation with segid+1 color
mjRND_CULL_FACE, // cull backward faces
mjNRNDFLAG // number of rendering flags
} mjtRndFlag;
typedef enum mjtStereo_ { // type of stereo rendering
mjSTEREO_NONE = 0, // no stereo; use left eye only
mjSTEREO_QUADBUFFERED, // quad buffered; revert to side-by-side if no hardware support
mjSTEREO_SIDEBYSIDE // side-by-side
} mjtStereo;
struct mjvPerturb_ { // object selection and perturbation
int select; // selected body id; non-positive: none
int flexselect; // selected flex id; negative: none
int skinselect; // selected skin id; negative: none
int active; // perturbation bitmask (mjtPertBit)
int active2; // secondary perturbation bitmask (mjtPertBit)
mjtNum refpos[3]; // reference position for selected object
mjtNum refquat[4]; // reference orientation for selected object
mjtNum refselpos[3]; // reference position for selection point
mjtNum localpos[3]; // selection point in object coordinates
mjtNum localmass; // spatial inertia at selection point
mjtNum scale; // relative mouse motion-to-space scaling (set by initPerturb)
};
typedef struct mjvPerturb_ mjvPerturb;
struct mjvCamera_ { // abstract camera
// type and ids
int type; // camera type (mjtCamera)
int fixedcamid; // fixed camera id
int trackbodyid; // body id to track
// abstract camera pose specification
mjtNum lookat[3]; // lookat point
mjtNum distance; // distance to lookat point or tracked body
mjtNum azimuth; // camera azimuth (deg)
mjtNum elevation; // camera elevation (deg)
// orthographic / perspective
int orthographic; // 0: perspective; 1: orthographic
};
typedef struct mjvCamera_ mjvCamera;
struct mjvGLCamera_ { // OpenGL camera
// camera frame
float pos[3]; // position
float forward[3]; // forward direction
float up[3]; // up direction
// camera projection
float frustum_center; // hor. center (left,right set to match aspect)
float frustum_width; // width (not used for rendering)
float frustum_bottom; // bottom
float frustum_top; // top
float frustum_near; // near
float frustum_far; // far
// orthographic / perspective
int orthographic; // 0: perspective; 1: orthographic
};
typedef struct mjvGLCamera_ mjvGLCamera;
struct mjvGeom_ { // abstract geom
// type info
int type; // geom type (mjtGeom)
int dataid; // mesh, hfield or plane id; -1: none; mesh: 2*id or 2*id+1 (hull)
int objtype; // mujoco object type; mjOBJ_UNKNOWN for decor
int objid; // mujoco object id; -1 for decor
int category; // visual category
int matid; // material id; -1: no textured material
int texcoord; // mesh or flex geom has texture coordinates
int segid; // segmentation id; -1: not shown
// spatial transform
float size[3]; // size parameters
float pos[3]; // Cartesian position
float mat[9]; // Cartesian orientation
// material properties
float rgba[4]; // color and transparency
float emission; // emission coef
float specular; // specular coef
float shininess; // shininess coef
float reflectance; // reflectance coef
char label[100]; // text label
// transparency rendering (set internally)
float camdist; // distance to camera (used by sorter)
float modelrbound; // geom rbound from model, 0 if not model geom
mjtByte transparent; // treat geom as transparent
};
typedef struct mjvGeom_ mjvGeom;
struct mjvLight_ { // OpenGL light
float pos[3]; // position rel. to body frame
float dir[3]; // direction rel. to body frame
int type; // type (mjtLightType)
int texid; // texture id for image lights
float attenuation[3]; // OpenGL attenuation (quadratic model)
float cutoff; // OpenGL cutoff
float exponent; // OpenGL exponent
float ambient[3]; // ambient rgb (alpha=1)
float diffuse[3]; // diffuse rgb (alpha=1)
float specular[3]; // specular rgb (alpha=1)
mjtByte headlight; // headlight
mjtByte castshadow; // does light cast shadows
float bulbradius; // bulb radius for soft shadows
float intensity; // intensity, in candelas
float range; // range of effectiveness
};
typedef struct mjvLight_ mjvLight;
struct mjvOption_ { // abstract visualization options
int label; // what objects to label (mjtLabel)
int frame; // which frame to show (mjtFrame)
mjtByte geomgroup[mjNGROUP]; // geom visualization by group
mjtByte sitegroup[mjNGROUP]; // site visualization by group
mjtByte jointgroup[mjNGROUP]; // joint visualization by group
mjtByte tendongroup[mjNGROUP]; // tendon visualization by group
mjtByte actuatorgroup[mjNGROUP]; // actuator visualization by group
mjtByte flexgroup[mjNGROUP]; // flex visualization by group
mjtByte skingroup[mjNGROUP]; // skin visualization by group
mjtByte flags[mjNVISFLAG]; // visualization flags (indexed by mjtVisFlag)
int bvh_depth; // depth of the bounding volume hierarchy to be visualized
int oct_depth; // depth of the octree to be visualized
int flex_layer; // element layer to be visualized for 3D flex
};
typedef struct mjvOption_ mjvOption;
struct mjvScene_ { // abstract scene passed to OpenGL renderer
// abstract geoms
int maxgeom; // size of allocated geom buffer
int ngeom; // number of geoms currently in buffer
mjvGeom* geoms; // buffer for geoms (ngeom)
int* geomorder; // buffer for ordering geoms by distance to camera (ngeom)
// flex data
int nflex; // number of flexes
int* flexedgeadr; // address of flex edges (nflex)
int* flexedgenum; // number of edges in flex (nflex)
int* flexvertadr; // address of flex vertices (nflex)
int* flexvertnum; // number of vertices in flex (nflex)
int* flexfaceadr; // address of flex faces (nflex)
int* flexfacenum; // number of flex faces allocated (nflex)
int* flexfaceused; // number of flex faces currently in use (nflex)
int* flexedge; // flex edge data (2*nflexedge)
float* flexvert; // flex vertices (3*nflexvert)
float* flexface; // flex faces vertices (9*sum(flexfacenum))
float* flexnormal; // flex face normals (9*sum(flexfacenum))
float* flextexcoord; // flex face texture coordinates (6*sum(flexfacenum))
mjtByte flexvertopt; // copy of mjVIS_FLEXVERT mjvOption flag
mjtByte flexedgeopt; // copy of mjVIS_FLEXEDGE mjvOption flag
mjtByte flexfaceopt; // copy of mjVIS_FLEXFACE mjvOption flag
mjtByte flexskinopt; // copy of mjVIS_FLEXSKIN mjvOption flag
// skin data
int nskin; // number of skins
int* skinfacenum; // number of faces in skin (nskin)
int* skinvertadr; // address of skin vertices (nskin)
int* skinvertnum; // number of vertices in skin (nskin)
float* skinvert; // skin vertex data (3*nskinvert)
float* skinnormal; // skin normal data (3*nskinvert)
// OpenGL lights
int nlight; // number of lights currently in buffer
mjvLight lights[mjMAXLIGHT]; // buffer for lights (nlight)
// OpenGL cameras
mjvGLCamera camera[2]; // left and right camera
// OpenGL model transformation
mjtByte enabletransform; // enable model transformation
float translate[3]; // model translation
float rotate[4]; // model quaternion rotation
float scale; // model scaling
// OpenGL rendering effects
int stereo; // stereoscopic rendering (mjtStereo)
mjtByte flags[mjNRNDFLAG]; // rendering flags (indexed by mjtRndFlag)
// framing
int framewidth; // frame pixel width; 0: disable framing
float framergb[3]; // frame color
};
typedef struct mjvScene_ mjvScene;
struct mjvFigure_ { // abstract 2D figure passed to OpenGL renderer
// enable flags
int flg_legend; // show legend
int flg_ticklabel[2]; // show grid tick labels (x,y)
int flg_extend; // automatically extend axis ranges to fit data
int flg_barplot; // isolated line segments (i.e. GL_LINES)
int flg_selection; // vertical selection line
int flg_symmetric; // symmetric y-axis
// style settings
float linewidth; // line width
float gridwidth; // grid line width
int gridsize[2]; // number of grid points in (x,y)
float gridrgb[3]; // grid line rgb
float figurergba[4]; // figure color and alpha
float panergba[4]; // pane color and alpha
float legendrgba[4]; // legend color and alpha
float textrgb[3]; // text color
float linergb[mjMAXLINE][3]; // line colors
float range[2][2]; // axis ranges; (min>=max) automatic
char xformat[20]; // x-tick label format for sprintf
char yformat[20]; // y-tick label format for sprintf
char minwidth[20]; // string used to determine min y-tick width
// text labels
char title[1000]; // figure title; subplots separated with 2+ spaces
char xlabel[100]; // x-axis label
char linename[mjMAXLINE][100]; // line names for legend
// dynamic settings
int legendoffset; // number of lines to offset legend
int subplot; // selected subplot (for title rendering)
int highlight[2]; // if point is in legend rect, highlight line
int highlightid; // if id>=0 and no point, highlight id
float selection; // selection line x-value
// line data
int linepnt[mjMAXLINE]; // number of points in line; (0) disable
float linedata[mjMAXLINE][2*mjMAXLINEPNT]; // line data (x,y)
// output from renderer
int xaxispixel[2]; // range of x-axis in pixels
int yaxispixel[2]; // range of y-axis in pixels
float xaxisdata[2]; // range of x-axis in data units
float yaxisdata[2]; // range of y-axis in data units
};
typedef struct mjvFigure_ mjvFigure;
//----------------------------- MJAPI FUNCTIONS --------------------------------
void mj_defaultVFS(mjVFS* vfs);
int mj_addFileVFS(mjVFS* vfs, const char* directory, const char* filename);
int mj_addBufferVFS(mjVFS* vfs, const char* name, const void* buffer, int nbuffer);
int mj_deleteFileVFS(mjVFS* vfs, const char* filename);
void mj_deleteVFS(mjVFS* vfs);
mjModel* mj_loadXML(const char* filename, const mjVFS* vfs, char* error, int error_sz);
mjSpec* mj_parseXML(const char* filename, const mjVFS* vfs, char* error, int error_sz);
mjSpec* mj_parseXMLString(const char* xml, const mjVFS* vfs, char* error, int error_sz);
mjModel* mj_compile(mjSpec* s, const mjVFS* vfs);
int mj_copyBack(mjSpec* s, const mjModel* m);
int mj_recompile(mjSpec* s, const mjVFS* vfs, mjModel* m, mjData* d);
int mj_saveLastXML(const char* filename, const mjModel* m, char* error, int error_sz);
void mj_freeLastXML(void);
int mj_saveXMLString(const mjSpec* s, char* xml, int xml_sz, char* error, int error_sz);
int mj_saveXML(const mjSpec* s, const char* filename, char* error, int error_sz);
void mj_step(const mjModel* m, mjData* d);
void mj_step1(const mjModel* m, mjData* d);
void mj_step2(const mjModel* m, mjData* d);
void mj_forward(const mjModel* m, mjData* d);
void mj_inverse(const mjModel* m, mjData* d);
void mj_forwardSkip(const mjModel* m, mjData* d, int skipstage, int skipsensor);
void mj_inverseSkip(const mjModel* m, mjData* d, int skipstage, int skipsensor);
void mj_defaultLROpt(mjLROpt* opt);
void mj_defaultSolRefImp(mjtNum* solref, mjtNum* solimp);
void mj_defaultOption(mjOption* opt);
void mj_defaultVisual(mjVisual* vis);
mjModel* mj_copyModel(mjModel* dest, const mjModel* src);
void mj_saveModel(const mjModel* m, const char* filename, void* buffer, int buffer_sz);
mjModel* mj_loadModel(const char* filename, const mjVFS* vfs);
void mj_deleteModel(mjModel* m);
int mj_sizeModel(const mjModel* m);
mjData* mj_makeData(const mjModel* m);
mjData* mj_copyData(mjData* dest, const mjModel* m, const mjData* src);
mjData* mjv_copyData(mjData* dest, const mjModel* m, const mjData* src);
void mj_resetData(const mjModel* m, mjData* d);
void mj_resetDataDebug(const mjModel* m, mjData* d, unsigned char debug_value);
void mj_resetDataKeyframe(const mjModel* m, mjData* d, int key);
void mj_markStack(mjData* d);
void mj_freeStack(mjData* d);
void* mj_stackAllocByte(mjData* d, size_t bytes, size_t alignment);
mjtNum* mj_stackAllocNum(mjData* d, size_t size);
int* mj_stackAllocInt(mjData* d, size_t size);
void mj_deleteData(mjData* d);
void mj_resetCallbacks(void);
void mj_setConst(mjModel* m, mjData* d);
int mj_setLengthRange(mjModel* m, mjData* d, int index,
const mjLROpt* opt, char* error, int error_sz);
mjSpec* mj_makeSpec(void);
mjSpec* mj_copySpec(const mjSpec* s);
void mj_deleteSpec(mjSpec* s);
int mjs_activatePlugin(mjSpec* s, const char* name);
int mjs_setDeepCopy(mjSpec* s, int deepcopy);
void mj_printFormattedModel(const mjModel* m, const char* filename, const char* float_format);
void mj_printModel(const mjModel* m, const char* filename);
void mj_printFormattedData(const mjModel* m, const mjData* d, const char* filename,
const char* float_format);
void mj_printData(const mjModel* m, const mjData* d, const char* filename);
void mju_printMat(const mjtNum* mat, int nr, int nc);
void mju_printMatSparse(const mjtNum* mat, int nr,
const int* rownnz, const int* rowadr, const int* colind);
int mj_printSchema(const char* filename, char* buffer, int buffer_sz,
int flg_html, int flg_pad);
void mj_fwdPosition(const mjModel* m, mjData* d);
void mj_fwdVelocity(const mjModel* m, mjData* d);
void mj_fwdActuation(const mjModel* m, mjData* d);
void mj_fwdAcceleration(const mjModel* m, mjData* d);
void mj_fwdConstraint(const mjModel* m, mjData* d);
void mj_Euler(const mjModel* m, mjData* d);
void mj_RungeKutta(const mjModel* m, mjData* d, int N);
void mj_implicit(const mjModel* m, mjData* d);
void mj_invPosition(const mjModel* m, mjData* d);
void mj_invVelocity(const mjModel* m, mjData* d);
void mj_invConstraint(const mjModel* m, mjData* d);
void mj_compareFwdInv(const mjModel* m, mjData* d);
void mj_sensorPos(const mjModel* m, mjData* d);
void mj_sensorVel(const mjModel* m, mjData* d);
void mj_sensorAcc(const mjModel* m, mjData* d);
void mj_energyPos(const mjModel* m, mjData* d);
void mj_energyVel(const mjModel* m, mjData* d);
void mj_checkPos(const mjModel* m, mjData* d);
void mj_checkVel(const mjModel* m, mjData* d);
void mj_checkAcc(const mjModel* m, mjData* d);
void mj_kinematics(const mjModel* m, mjData* d);
void mj_comPos(const mjModel* m, mjData* d);
void mj_camlight(const mjModel* m, mjData* d);
void mj_flex(const mjModel* m, mjData* d);
void mj_tendon(const mjModel* m, mjData* d);
void mj_transmission(const mjModel* m, mjData* d);
void mj_crb(const mjModel* m, mjData* d);
void mj_makeM(const mjModel* m, mjData* d);
void mj_factorM(const mjModel* m, mjData* d);
void mj_solveM(const mjModel* m, mjData* d, mjtNum* x, const mjtNum* y, int n);
void mj_solveM2(const mjModel* m, mjData* d, mjtNum* x, const mjtNum* y,
const mjtNum* sqrtInvD, int n);
void mj_comVel(const mjModel* m, mjData* d);
void mj_passive(const mjModel* m, mjData* d);
void mj_subtreeVel(const mjModel* m, mjData* d);
void mj_rne(const mjModel* m, mjData* d, int flg_acc, mjtNum* result);
void mj_rnePostConstraint(const mjModel* m, mjData* d);
void mj_collision(const mjModel* m, mjData* d);
void mj_makeConstraint(const mjModel* m, mjData* d);
void mj_island(const mjModel* m, mjData* d);
void mj_projectConstraint(const mjModel* m, mjData* d);
void mj_referenceConstraint(const mjModel* m, mjData* d);
void mj_constraintUpdate(const mjModel* m, mjData* d, const mjtNum* jar,
mjtNum cost[1], int flg_coneHessian);
int mj_stateSize(const mjModel* m, unsigned int spec);
void mj_getState(const mjModel* m, const mjData* d, mjtNum* state, unsigned int spec);
void mj_setState(const mjModel* m, mjData* d, const mjtNum* state, unsigned int spec);
void mj_setKeyframe(mjModel* m, const mjData* d, int k);
int mj_addContact(const mjModel* m, mjData* d, const mjContact* con);
int mj_isPyramidal(const mjModel* m);
int mj_isSparse(const mjModel* m);
int mj_isDual(const mjModel* m);
void mj_mulJacVec(const mjModel* m, const mjData* d, mjtNum* res, const mjtNum* vec);
void mj_mulJacTVec(const mjModel* m, const mjData* d, mjtNum* res, const mjtNum* vec);
void mj_jac(const mjModel* m, const mjData* d, mjtNum* jacp, mjtNum* jacr,
const mjtNum point[3], int body);
void mj_jacBody(const mjModel* m, const mjData* d, mjtNum* jacp, mjtNum* jacr, int body);
void mj_jacBodyCom(const mjModel* m, const mjData* d, mjtNum* jacp, mjtNum* jacr, int body);
void mj_jacSubtreeCom(const mjModel* m, mjData* d, mjtNum* jacp, int body);
void mj_jacGeom(const mjModel* m, const mjData* d, mjtNum* jacp, mjtNum* jacr, int geom);
void mj_jacSite(const mjModel* m, const mjData* d, mjtNum* jacp, mjtNum* jacr, int site);
void mj_jacPointAxis(const mjModel* m, mjData* d, mjtNum* jacPoint, mjtNum* jacAxis,
const mjtNum point[3], const mjtNum axis[3], int body);
void mj_jacDot(const mjModel* m, const mjData* d, mjtNum* jacp, mjtNum* jacr,
const mjtNum point[3], int body);
void mj_angmomMat(const mjModel* m, mjData* d, mjtNum* mat, int body);
int mj_name2id(const mjModel* m, int type, const char* name);
const char* mj_id2name(const mjModel* m, int type, int id);
void mj_fullM(const mjModel* m, mjtNum* dst, const mjtNum* M);
void mj_mulM(const mjModel* m, const mjData* d, mjtNum* res, const mjtNum* vec);
void mj_mulM2(const mjModel* m, const mjData* d, mjtNum* res, const mjtNum* vec);
void mj_addM(const mjModel* m, mjData* d, mjtNum* dst, int* rownnz, int* rowadr, int* colind);
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);
void mj_objectVelocity(const mjModel* m, const mjData* d,
int objtype, int objid, mjtNum res[6], int flg_local);
void mj_objectAcceleration(const mjModel* m, const mjData* d,
int objtype, int objid, mjtNum res[6], int flg_local);
mjtNum mj_geomDistance(const mjModel* m, const mjData* d, int geom1, int geom2,
mjtNum distmax, mjtNum fromto[6]);
void mj_contactForce(const mjModel* m, const mjData* d, int id, mjtNum result[6]);
void mj_differentiatePos(const mjModel* m, mjtNum* qvel, mjtNum dt,
const mjtNum* qpos1, const mjtNum* qpos2);
void mj_integratePos(const mjModel* m, mjtNum* qpos, const mjtNum* qvel, mjtNum dt);
void mj_normalizeQuat(const mjModel* m, mjtNum* qpos);
void mj_local2Global(mjData* d, mjtNum xpos[3], mjtNum xmat[9], const mjtNum pos[3],
const mjtNum quat[4], int body, mjtByte sameframe);
mjtNum mj_getTotalmass(const mjModel* m);
void mj_setTotalmass(mjModel* m, mjtNum newmass);
const char* mj_getPluginConfig(const mjModel* m, int plugin_id, const char* attrib);
void mj_loadPluginLibrary(const char* path);
void mj_loadAllPluginLibraries(const char* directory, mjfPluginLibraryLoadCallback callback);
int mj_version(void);
const char* mj_versionString(void);
void mj_multiRay(const mjModel* m, mjData* d, const mjtNum pnt[3], const mjtNum* vec,
const mjtByte* geomgroup, mjtByte flg_static, int bodyexclude,
int* geomid, mjtNum* dist, int nray, mjtNum cutoff);
mjtNum mj_ray(const mjModel* m, const mjData* d, const mjtNum pnt[3], const mjtNum vec[3],
const mjtByte* geomgroup, mjtByte flg_static, int bodyexclude,
int geomid[1]);
mjtNum mj_rayHfield(const mjModel* m, const mjData* d, int geomid,
const mjtNum pnt[3], const mjtNum vec[3]);
mjtNum mj_rayMesh(const mjModel* m, const mjData* d, int geomid,
const mjtNum pnt[3], const mjtNum vec[3]);
mjtNum mju_rayGeom(const mjtNum pos[3], const mjtNum mat[9], const mjtNum size[3],
const mjtNum pnt[3], const mjtNum vec[3], int geomtype);
mjtNum mju_rayFlex(const mjModel* m, const mjData* d, int flex_layer, mjtByte flg_vert,
mjtByte flg_edge, mjtByte flg_face, mjtByte flg_skin, int flexid,
const mjtNum* pnt, const mjtNum* vec, int vertid[1]);
mjtNum mju_raySkin(int nface, int nvert, const int* face, const float* vert,
const mjtNum pnt[3], const mjtNum vec[3], int vertid[1]);
void mjv_defaultCamera(mjvCamera* cam);
void mjv_defaultFreeCamera(const mjModel* m, mjvCamera* cam);
void mjv_defaultPerturb(mjvPerturb* pert);
void mjv_room2model(mjtNum modelpos[3], mjtNum modelquat[4], const mjtNum roompos[3],
const mjtNum roomquat[4], const mjvScene* scn);
void mjv_model2room(mjtNum roompos[3], mjtNum roomquat[4], const mjtNum modelpos[3],
const mjtNum modelquat[4], const mjvScene* scn);
void mjv_cameraInModel(mjtNum headpos[3], mjtNum forward[3], mjtNum up[3],
const mjvScene* scn);
void mjv_cameraInRoom(mjtNum headpos[3], mjtNum forward[3], mjtNum up[3],
const mjvScene* scn);
mjtNum mjv_frustumHeight(const mjvScene* scn);
void mjv_alignToCamera(mjtNum res[3], const mjtNum vec[3], const mjtNum forward[3]);
void mjv_moveCamera(const mjModel* m, int action, mjtNum reldx, mjtNum reldy,
const mjvScene* scn, mjvCamera* cam);
void mjv_movePerturb(const mjModel* m, const mjData* d, int action, mjtNum reldx,
mjtNum reldy, const mjvScene* scn, mjvPerturb* pert);
void mjv_moveModel(const mjModel* m, int action, mjtNum reldx, mjtNum reldy,
const mjtNum roomup[3], mjvScene* scn);
void mjv_initPerturb(const mjModel* m, mjData* d, const mjvScene* scn, mjvPerturb* pert);
void mjv_applyPerturbPose(const mjModel* m, mjData* d, const mjvPerturb* pert,
int flg_paused);
void mjv_applyPerturbForce(const mjModel* m, mjData* d, const mjvPerturb* pert);
mjvGLCamera mjv_averageCamera(const mjvGLCamera* cam1, const mjvGLCamera* cam2);
int mjv_select(const mjModel* m, const mjData* d, const mjvOption* vopt,
mjtNum aspectratio, mjtNum relx, mjtNum rely,
const mjvScene* scn, mjtNum selpnt[3],
int geomid[1], int flexid[1], int skinid[1]);
void mjv_defaultOption(mjvOption* opt);
void mjv_defaultFigure(mjvFigure* fig);
void mjv_initGeom(mjvGeom* geom, int type, const mjtNum size[3],
const mjtNum pos[3], const mjtNum mat[9], const float rgba[4]);
void mjv_connector(mjvGeom* geom, int type, mjtNum width,
const mjtNum from[3], const mjtNum to[3]);
void mjv_defaultScene(mjvScene* scn);
void mjv_makeScene(const mjModel* m, mjvScene* scn, int maxgeom);
void mjv_freeScene(mjvScene* scn);
void mjv_updateScene(const mjModel* m, mjData* d, const mjvOption* opt,
const mjvPerturb* pert, mjvCamera* cam, int catmask, mjvScene* scn);
void mjv_copyModel(mjModel* dest, const mjModel* src);
void mjv_addGeoms(const mjModel* m, mjData* d, const mjvOption* opt,
const mjvPerturb* pert, int catmask, mjvScene* scn);
void mjv_makeLights(const mjModel* m, const mjData* d, mjvScene* scn);
void mjv_updateCamera(const mjModel* m, const mjData* d, mjvCamera* cam, mjvScene* scn);
void mjv_updateSkin(const mjModel* m, const mjData* d, mjvScene* scn);
void mjr_defaultContext(mjrContext* con);
void mjr_makeContext(const mjModel* m, mjrContext* con, int fontscale);
void mjr_changeFont(int fontscale, mjrContext* con);
void mjr_addAux(int index, int width, int height, int samples, mjrContext* con);
void mjr_freeContext(mjrContext* con);
void mjr_resizeOffscreen(int width, int height, mjrContext* con);
void mjr_uploadTexture(const mjModel* m, const mjrContext* con, int texid);
void mjr_uploadMesh(const mjModel* m, const mjrContext* con, int meshid);
void mjr_uploadHField(const mjModel* m, const mjrContext* con, int hfieldid);
void mjr_restoreBuffer(const mjrContext* con);
void mjr_setBuffer(int framebuffer, mjrContext* con);
void mjr_readPixels(unsigned char* rgb, float* depth,
mjrRect viewport, const mjrContext* con);
void mjr_drawPixels(const unsigned char* rgb, const float* depth,
mjrRect viewport, const mjrContext* con);
void mjr_blitBuffer(mjrRect src, mjrRect dst,
int flg_color, int flg_depth, const mjrContext* con);
void mjr_setAux(int index, const mjrContext* con);
void mjr_blitAux(int index, mjrRect src, int left, int bottom, const mjrContext* con);
void mjr_text(int font, const char* txt, const mjrContext* con,
float x, float y, float r, float g, float b);
void mjr_overlay(int font, int gridpos, mjrRect viewport,
const char* overlay, const char* overlay2, const mjrContext* con);
mjrRect mjr_maxViewport(const mjrContext* con);
void mjr_rectangle(mjrRect viewport, float r, float g, float b, float a);
void mjr_label(mjrRect viewport, int font, const char* txt,
float r, float g, float b, float a, float rt, float gt, float bt,
const mjrContext* con);
void mjr_figure(mjrRect viewport, mjvFigure* fig, const mjrContext* con);
void mjr_render(mjrRect viewport, mjvScene* scn, const mjrContext* con);
void mjr_finish(void);
int mjr_getError(void);
int mjr_findRect(int x, int y, int nrect, const mjrRect* rect);
mjuiThemeSpacing mjui_themeSpacing(int ind);
mjuiThemeColor mjui_themeColor(int ind);
void mjui_add(mjUI* ui, const mjuiDef* def);
void mjui_addToSection(mjUI* ui, int sect, const mjuiDef* def);
void mjui_resize(mjUI* ui, const mjrContext* con);
void mjui_update(int section, int item, const mjUI* ui,
const mjuiState* state, const mjrContext* con);
mjuiItem* mjui_event(mjUI* ui, mjuiState* state, const mjrContext* con);
void mjui_render(mjUI* ui, const mjuiState* state, const mjrContext* con);
void mju_error(const char* msg, ...) mjPRINTFLIKE(1, 2);
void mju_error_i(const char* msg, int i);
void mju_error_s(const char* msg, const char* text);
void mju_warning(const char* msg, ...) mjPRINTFLIKE(1, 2);
void mju_warning_i(const char* msg, int i);
void mju_warning_s(const char* msg, const char* text);
void mju_clearHandlers(void);
void* mju_malloc(size_t size);
void mju_free(void* ptr);
void mj_warning(mjData* d, int warning, int info);
void mju_writeLog(const char* type, const char* msg);
const char* mjs_getError(mjSpec* s);
int mjs_isWarning(mjSpec* s);
void mju_zero3(mjtNum res[3]);
void mju_copy3(mjtNum res[3], const mjtNum data[3]);
void mju_scl3(mjtNum res[3], const mjtNum vec[3], mjtNum scl);
void mju_add3(mjtNum res[3], const mjtNum vec1[3], const mjtNum vec2[3]);
void mju_sub3(mjtNum res[3], const mjtNum vec1[3], const mjtNum vec2[3]);
void mju_addTo3(mjtNum res[3], const mjtNum vec[3]);
void mju_subFrom3(mjtNum res[3], const mjtNum vec[3]);
void mju_addToScl3(mjtNum res[3], const mjtNum vec[3], mjtNum scl);
void mju_addScl3(mjtNum res[3], const mjtNum vec1[3], const mjtNum vec2[3], mjtNum scl);
mjtNum mju_normalize3(mjtNum vec[3]);
mjtNum mju_norm3(const mjtNum vec[3]);
mjtNum mju_dot3(const mjtNum vec1[3], const mjtNum vec2[3]);
mjtNum mju_dist3(const mjtNum pos1[3], const mjtNum pos2[3]);
void mju_mulMatVec3(mjtNum res[3], const mjtNum mat[9], const mjtNum vec[3]);
void mju_mulMatTVec3(mjtNum res[3], const mjtNum mat[9], const mjtNum vec[3]);
void mju_cross(mjtNum res[3], const mjtNum a[3], const mjtNum b[3]);
void mju_zero4(mjtNum res[4]);
void mju_unit4(mjtNum res[4]);
void mju_copy4(mjtNum res[4], const mjtNum data[4]);
mjtNum mju_normalize4(mjtNum vec[4]);
void mju_zero(mjtNum* res, int n);
void mju_fill(mjtNum* res, mjtNum val, int n);
void mju_copy(mjtNum* res, const mjtNum* vec, int n);
mjtNum mju_sum(const mjtNum* vec, int n);
mjtNum mju_L1(const mjtNum* vec, int n);
void mju_scl(mjtNum* res, const mjtNum* vec, mjtNum scl, int n);
void mju_add(mjtNum* res, const mjtNum* vec1, const mjtNum* vec2, int n);
void mju_sub(mjtNum* res, const mjtNum* vec1, const mjtNum* vec2, int n);
void mju_addTo(mjtNum* res, const mjtNum* vec, int n);
void mju_subFrom(mjtNum* res, const mjtNum* vec, int n);
void mju_addToScl(mjtNum* res, const mjtNum* vec, mjtNum scl, int n);
void mju_addScl(mjtNum* res, const mjtNum* vec1, const mjtNum* vec2, mjtNum scl, int n);
mjtNum mju_normalize(mjtNum* res, int n);
mjtNum mju_norm(const mjtNum* res, int n);
mjtNum mju_dot(const mjtNum* vec1, const mjtNum* vec2, int n);
void mju_mulMatVec(mjtNum* res, const mjtNum* mat, const mjtNum* vec, int nr, int nc);
void mju_mulMatTVec(mjtNum* res, const mjtNum* mat, const mjtNum* vec, int nr, int nc);
mjtNum mju_mulVecMatVec(const mjtNum* vec1, const mjtNum* mat, const mjtNum* vec2, int n);
void mju_transpose(mjtNum* res, const mjtNum* mat, int nr, int nc);
void mju_symmetrize(mjtNum* res, const mjtNum* mat, int n);
void mju_eye(mjtNum* mat, int n);
void mju_mulMatMat(mjtNum* res, const mjtNum* mat1, const mjtNum* mat2,
int r1, int c1, int c2);
void mju_mulMatMatT(mjtNum* res, const mjtNum* mat1, const mjtNum* mat2,
int r1, int c1, int r2);
void mju_mulMatTMat(mjtNum* res, const mjtNum* mat1, const mjtNum* mat2,
int r1, int c1, int c2);
void mju_sqrMatTD(mjtNum* res, const mjtNum* mat, const mjtNum* diag, int nr, int nc);
void mju_transformSpatial(mjtNum res[6], const mjtNum vec[6], int flg_force,
const mjtNum newpos[3], const mjtNum oldpos[3],
const mjtNum rotnew2old[9]);
int mju_dense2sparse(mjtNum* res, const mjtNum* mat, int nr, int nc,
int* rownnz, int* rowadr, int* colind, int nnz);
void mju_sparse2dense(mjtNum* res, const mjtNum* mat, int nr, int nc,
const int* rownnz, const int* rowadr, const int* colind);
void mju_rotVecQuat(mjtNum res[3], const mjtNum vec[3], const mjtNum quat[4]);
void mju_negQuat(mjtNum res[4], const mjtNum quat[4]);
void mju_mulQuat(mjtNum res[4], const mjtNum quat1[4], const mjtNum quat2[4]);
void mju_mulQuatAxis(mjtNum res[4], const mjtNum quat[4], const mjtNum axis[3]);
void mju_axisAngle2Quat(mjtNum res[4], const mjtNum axis[3], mjtNum angle);
void mju_quat2Vel(mjtNum res[3], const mjtNum quat[4], mjtNum dt);
void mju_subQuat(mjtNum res[3], const mjtNum qa[4], const mjtNum qb[4]);
void mju_quat2Mat(mjtNum res[9], const mjtNum quat[4]);
void mju_mat2Quat(mjtNum quat[4], const mjtNum mat[9]);
void mju_derivQuat(mjtNum res[4], const mjtNum quat[4], const mjtNum vel[3]);
void mju_quatIntegrate(mjtNum quat[4], const mjtNum vel[3], mjtNum scale);
void mju_quatZ2Vec(mjtNum quat[4], const mjtNum vec[3]);
int mju_mat2Rot(mjtNum quat[4], const mjtNum mat[9]);
void mju_euler2Quat(mjtNum quat[4], const mjtNum euler[3], const char* seq);
void mju_mulPose(mjtNum posres[3], mjtNum quatres[4],
const mjtNum pos1[3], const mjtNum quat1[4],
const mjtNum pos2[3], const mjtNum quat2[4]);
void mju_negPose(mjtNum posres[3], mjtNum quatres[4],
const mjtNum pos[3], const mjtNum quat[4]);
void mju_trnVecPose(mjtNum res[3], const mjtNum pos[3], const mjtNum quat[4],
const mjtNum vec[3]);
int mju_cholFactor(mjtNum* mat, int n, mjtNum mindiag);
void mju_cholSolve(mjtNum* res, const mjtNum* mat, const mjtNum* vec, int n);
int mju_cholUpdate(mjtNum* mat, mjtNum* x, int n, int flg_plus);
mjtNum mju_cholFactorBand(mjtNum* mat, int ntotal, int nband, int ndense,
mjtNum diagadd, mjtNum diagmul);
void mju_cholSolveBand(mjtNum* res, const mjtNum* mat, const mjtNum* vec,
int ntotal, int nband, int ndense);
void mju_band2Dense(mjtNum* res, const mjtNum* mat, int ntotal, int nband, int ndense,
mjtByte flg_sym);
void mju_dense2Band(mjtNum* res, const mjtNum* mat, int ntotal, int nband, int ndense);
void mju_bandMulMatVec(mjtNum* res, const mjtNum* mat, const mjtNum* vec,
int ntotal, int nband, int ndense, int nvec, mjtByte flg_sym);
int mju_bandDiag(int i, int ntotal, int nband, int ndense);
int mju_eig3(mjtNum eigval[3], mjtNum eigvec[9], mjtNum quat[4], const mjtNum mat[9]);
int mju_boxQP(mjtNum* res, mjtNum* R, int* index, const mjtNum* H, const mjtNum* g, int n,
const mjtNum* lower, const mjtNum* upper);
void mju_boxQPmalloc(mjtNum** res, mjtNum** R, int** index, mjtNum** H, mjtNum** g, int n,
mjtNum** lower, mjtNum** upper);
mjtNum mju_muscleGain(mjtNum len, mjtNum vel, const mjtNum lengthrange[2],
mjtNum acc0, const mjtNum prm[9]);
mjtNum mju_muscleBias(mjtNum len, const mjtNum lengthrange[2],
mjtNum acc0, const mjtNum prm[9]);
mjtNum mju_muscleDynamics(mjtNum ctrl, mjtNum act, const mjtNum prm[3]);
void mju_encodePyramid(mjtNum* pyramid, const mjtNum* force, const mjtNum* mu, int dim);
void mju_decodePyramid(mjtNum* force, const mjtNum* pyramid, const mjtNum* mu, int dim);
mjtNum mju_springDamper(mjtNum pos0, mjtNum vel0, mjtNum Kp, mjtNum Kv, mjtNum dt);
mjtNum mju_min(mjtNum a, mjtNum b);
mjtNum mju_max(mjtNum a, mjtNum b);
mjtNum mju_clip(mjtNum x, mjtNum min, mjtNum max);
mjtNum mju_sign(mjtNum x);
int mju_round(mjtNum x);
const char* mju_type2Str(int type);
int mju_str2Type(const char* str);
const char* mju_writeNumBytes(size_t nbytes);
const char* mju_warningText(int warning, size_t info);
int mju_isBad(mjtNum x);
int mju_isZero(mjtNum* vec, int n);
mjtNum mju_standardNormal(mjtNum* num2);
void mju_f2n(mjtNum* res, const float* vec, int n);
void mju_n2f(float* res, const mjtNum* vec, int n);
void mju_d2n(mjtNum* res, const double* vec, int n);
void mju_n2d(double* res, const mjtNum* vec, int n);
void mju_insertionSort(mjtNum* list, int n);
void mju_insertionSortInt(int* list, int n);
mjtNum mju_Halton(int index, int base);
char* mju_strncpy(char *dst, const char *src, int n);
mjtNum mju_sigmoid(mjtNum x);
const mjpPlugin* mjc_getSDF(const mjModel* m, int id);
mjtNum mjc_distance(const mjModel* m, const mjData* d, const mjSDF* s, const mjtNum x[3]);
void mjc_gradient(const mjModel* m, const mjData* d, const mjSDF* s, mjtNum gradient[3],
const mjtNum x[3]);
void mjd_transitionFD(const mjModel* m, mjData* d, mjtNum eps, mjtByte flg_centered,
mjtNum* A, mjtNum* B, mjtNum* C, mjtNum* D);
void mjd_inverseFD(const mjModel* m, mjData* d, mjtNum eps, mjtByte flg_actuation,
mjtNum *DfDq, mjtNum *DfDv, mjtNum *DfDa,
mjtNum *DsDq, mjtNum *DsDv, mjtNum *DsDa,
mjtNum *DmDq);
void mjd_subQuat(const mjtNum qa[4], const mjtNum qb[4], mjtNum Da[9], mjtNum Db[9]);
void mjd_quatIntegrate(const mjtNum vel[3], mjtNum scale,
mjtNum Dquat[9], mjtNum Dvel[9], mjtNum Dscale[3]);
void mjp_defaultPlugin(mjpPlugin* plugin);
int mjp_registerPlugin(const mjpPlugin* plugin);
int mjp_pluginCount(void);
const mjpPlugin* mjp_getPlugin(const char* name, int* slot);
const mjpPlugin* mjp_getPluginAtSlot(int slot);
void mjp_defaultResourceProvider(mjpResourceProvider* provider);
int mjp_registerResourceProvider(const mjpResourceProvider* provider);
int mjp_resourceProviderCount(void);
const mjpResourceProvider* mjp_getResourceProvider(const char* resource_name);
const mjpResourceProvider* mjp_getResourceProviderAtSlot(int slot);
mjThreadPool* mju_threadPoolCreate(size_t number_of_threads);
void mju_bindThreadPool(mjData* d, void* thread_pool);
void mju_threadPoolEnqueue(mjThreadPool* thread_pool, mjTask* task);
void mju_threadPoolDestroy(mjThreadPool* thread_pool);
void mju_defaultTask(mjTask* task);
void mju_taskJoin(mjTask* task);
mjsElement* mjs_attach(mjsElement* parent, const mjsElement* child,
const char* prefix, const char* suffix);
mjsBody* mjs_addBody(mjsBody* body, const mjsDefault* def);
mjsSite* mjs_addSite(mjsBody* body, const mjsDefault* def);
mjsJoint* mjs_addJoint(mjsBody* body, const mjsDefault* def);
mjsJoint* mjs_addFreeJoint(mjsBody* body);
mjsGeom* mjs_addGeom(mjsBody* body, const mjsDefault* def);
mjsCamera* mjs_addCamera(mjsBody* body, const mjsDefault* def);
mjsLight* mjs_addLight(mjsBody* body, const mjsDefault* def);
mjsFrame* mjs_addFrame(mjsBody* body, mjsFrame* parentframe);
int mjs_delete(mjSpec* spec, mjsElement* element);
mjsActuator* mjs_addActuator(mjSpec* s, const mjsDefault* def);
mjsSensor* mjs_addSensor(mjSpec* s);
mjsFlex* mjs_addFlex(mjSpec* s);
mjsPair* mjs_addPair(mjSpec* s, const mjsDefault* def);
mjsExclude* mjs_addExclude(mjSpec* s);
mjsEquality* mjs_addEquality(mjSpec* s, const mjsDefault* def);
mjsTendon* mjs_addTendon(mjSpec* s, const mjsDefault* def);
mjsWrap* mjs_wrapSite(mjsTendon* tendon, const char* name);
mjsWrap* mjs_wrapGeom(mjsTendon* tendon, const char* name, const char* sidesite);
mjsWrap* mjs_wrapJoint(mjsTendon* tendon, const char* name, double coef);
mjsWrap* mjs_wrapPulley(mjsTendon* tendon, double divisor);
mjsNumeric* mjs_addNumeric(mjSpec* s);
mjsText* mjs_addText(mjSpec* s);
mjsTuple* mjs_addTuple(mjSpec* s);
mjsKey* mjs_addKey(mjSpec* s);
mjsPlugin* mjs_addPlugin(mjSpec* s);
mjsDefault* mjs_addDefault(mjSpec* s, const char* classname, const mjsDefault* parent);
const char* mjs_setToMotor(mjsActuator* actuator);
const char* mjs_setToPosition(mjsActuator* actuator, double kp, double kv[1],
double dampratio[1], double timeconst[1], double inheritrange);
const char* mjs_setToIntVelocity(mjsActuator* actuator, double kp, double kv[1],
double dampratio[1], double timeconst[1], double inheritrange);
const char* mjs_setToVelocity(mjsActuator* actuator, double kv);
const char* mjs_setToDamper(mjsActuator* actuator, double kv);
const char* mjs_setToCylinder(mjsActuator* actuator, double timeconst,
double bias, double area, double diameter);
const char* mjs_setToMuscle(mjsActuator* actuator, double timeconst[2], double tausmooth,
double range[2], double force, double scale, double lmin,
double lmax, double vmax, double fpmax, double fvmax);
const char* mjs_setToAdhesion(mjsActuator* actuator, double gain);
mjsMesh* mjs_addMesh(mjSpec* s, const mjsDefault* def);
mjsHField* mjs_addHField(mjSpec* s);
mjsSkin* mjs_addSkin(mjSpec* s);
mjsTexture* mjs_addTexture(mjSpec* s);
mjsMaterial* mjs_addMaterial(mjSpec* s, const mjsDefault* def);
mjSpec* mjs_getSpec(mjsElement* element);
mjSpec* mjs_findSpec(mjSpec* spec, const char* name);
mjsBody* mjs_findBody(mjSpec* s, const char* name);
mjsElement* mjs_findElement(mjSpec* s, mjtObj type, const char* name);
mjsBody* mjs_findChild(mjsBody* body, const char* name);
mjsBody* mjs_getParent(mjsElement* element);
mjsFrame* mjs_getFrame(mjsElement* element);
mjsFrame* mjs_findFrame(mjSpec* s, const char* name);
mjsDefault* mjs_getDefault(mjsElement* element);
mjsDefault* mjs_findDefault(mjSpec* s, const char* classname);
mjsDefault* mjs_getSpecDefault(mjSpec* s);
int mjs_getId(mjsElement* element);
mjsElement* mjs_firstChild(mjsBody* body, mjtObj type, int recurse);
mjsElement* mjs_nextChild(mjsBody* body, mjsElement* child, int recurse);
mjsElement* mjs_firstElement(mjSpec* s, mjtObj type);
mjsElement* mjs_nextElement(mjSpec* s, mjsElement* element);
int mjs_setName(mjsElement* element, const char* name);
void mjs_setBuffer(mjByteVec* dest, const void* array, int size);
void mjs_setString(mjString* dest, const char* text);
void mjs_setStringVec(mjStringVec* dest, const char* text);
mjtByte mjs_setInStringVec(mjStringVec* dest, int i, const char* text);
void mjs_appendString(mjStringVec* dest, const char* text);
void mjs_setInt(mjIntVec* dest, const int* array, int size);
void mjs_appendIntVec(mjIntVecVec* dest, const int* array, int size);
void mjs_setFloat(mjFloatVec* dest, const float* array, int size);
void mjs_appendFloatVec(mjFloatVecVec* dest, const float* array, int size);
void mjs_setDouble(mjDoubleVec* dest, const double* array, int size);
void mjs_setPluginAttributes(mjsPlugin* plugin, void* attributes);
mjString* mjs_getName(mjsElement* element);
const char* mjs_getString(const mjString* source);
const double* mjs_getDouble(const mjDoubleVec* source, int* size);
const void* mjs_getPluginAttributes(const mjsPlugin* plugin);
void mjs_setDefault(mjsElement* element, const mjsDefault* def);
int mjs_setFrame(mjsElement* dest, mjsFrame* frame);
const char* mjs_resolveOrientation(double quat[4], mjtByte degree, const char* sequence,
const mjsOrientation* orientation);
mjsFrame* mjs_bodyToFrame(mjsBody** body);
void mjs_setUserValue(mjsElement* element, const char* key, const void* data);
void mjs_setUserValueWithCleanup(mjsElement* element, const char* key,
const void* data,
void (*cleanup)(const void*));
const void* mjs_getUserValue(mjsElement* element, const char* key);
void mjs_deleteUserValue(mjsElement* element, const char* key);
void mjs_defaultSpec(mjSpec* spec);
void mjs_defaultOrientation(mjsOrientation* orient);
void mjs_defaultBody(mjsBody* body);
void mjs_defaultFrame(mjsFrame* frame);
void mjs_defaultJoint(mjsJoint* joint);
void mjs_defaultGeom(mjsGeom* geom);
void mjs_defaultSite(mjsSite* site);
void mjs_defaultCamera(mjsCamera* camera);
void mjs_defaultLight(mjsLight* light);
void mjs_defaultFlex(mjsFlex* flex);
void mjs_defaultMesh(mjsMesh* mesh);
void mjs_defaultHField(mjsHField* hfield);
void mjs_defaultSkin(mjsSkin* skin);
void mjs_defaultTexture(mjsTexture* texture);
void mjs_defaultMaterial(mjsMaterial* material);
void mjs_defaultPair(mjsPair* pair);
void mjs_defaultEquality(mjsEquality* equality);
void mjs_defaultTendon(mjsTendon* tendon);
void mjs_defaultActuator(mjsActuator* actuator);
void mjs_defaultSensor(mjsSensor* sensor);
void mjs_defaultNumeric(mjsNumeric* numeric);
void mjs_defaultText(mjsText* text);
void mjs_defaultTuple(mjsTuple* tuple);
void mjs_defaultKey(mjsKey* key);
void mjs_defaultPlugin(mjsPlugin* plugin);
mjsBody* mjs_asBody(mjsElement* element);
mjsGeom* mjs_asGeom(mjsElement* element);
mjsJoint* mjs_asJoint(mjsElement* element);
mjsSite* mjs_asSite(mjsElement* element);
mjsCamera* mjs_asCamera(mjsElement* element);
mjsLight* mjs_asLight(mjsElement* element);
mjsFrame* mjs_asFrame(mjsElement* element);
mjsActuator* mjs_asActuator(mjsElement* element);
mjsSensor* mjs_asSensor(mjsElement* element);
mjsFlex* mjs_asFlex(mjsElement* element);
mjsPair* mjs_asPair(mjsElement* element);
mjsEquality* mjs_asEquality(mjsElement* element);
mjsExclude* mjs_asExclude(mjsElement* element);
mjsTendon* mjs_asTendon(mjsElement* element);
mjsNumeric* mjs_asNumeric(mjsElement* element);
mjsText* mjs_asText(mjsElement* element);
mjsTuple* mjs_asTuple(mjsElement* element);
mjsKey* mjs_asKey(mjsElement* element);
mjsMesh* mjs_asMesh(mjsElement* element);
mjsHField* mjs_asHField(mjsElement* element);
mjsSkin* mjs_asSkin(mjsElement* element);
mjsTexture* mjs_asTexture(mjsElement* element);
mjsMaterial* mjs_asMaterial(mjsElement* element);
mjsPlugin* mjs_asPlugin(mjsElement* element);
// NOLINTEND
|