File size: 114,178 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 3541 3542 3543 3544 3545 3546 3547 3548 3549 3550 3551 3552 3553 3554 3555 3556 3557 3558 3559 3560 3561 3562 3563 3564 3565 3566 3567 3568 3569 3570 3571 3572 3573 3574 3575 3576 3577 3578 3579 3580 3581 3582 3583 3584 3585 3586 3587 3588 3589 3590 3591 3592 3593 3594 3595 3596 3597 3598 3599 3600 3601 3602 3603 3604 3605 3606 3607 3608 3609 3610 3611 3612 3613 3614 3615 3616 3617 3618 3619 3620 3621 3622 3623 3624 3625 3626 3627 3628 3629 3630 3631 3632 3633 3634 3635 3636 3637 3638 3639 3640 3641 3642 3643 3644 3645 3646 3647 3648 3649 3650 3651 3652 3653 3654 3655 3656 3657 3658 3659 3660 3661 3662 3663 3664 3665 3666 3667 3668 3669 3670 3671 3672 3673 3674 3675 3676 3677 3678 3679 3680 3681 3682 3683 3684 3685 3686 3687 3688 3689 3690 3691 3692 3693 3694 3695 3696 3697 3698 3699 3700 3701 3702 3703 3704 3705 3706 3707 3708 3709 3710 3711 3712 3713 3714 3715 3716 3717 3718 3719 3720 3721 3722 3723 3724 3725 3726 3727 3728 3729 3730 3731 3732 3733 3734 3735 3736 3737 3738 3739 3740 3741 3742 3743 3744 3745 3746 3747 3748 3749 3750 3751 3752 3753 3754 3755 3756 3757 3758 3759 3760 3761 3762 3763 3764 3765 3766 3767 3768 3769 3770 3771 3772 3773 3774 3775 3776 3777 3778 3779 3780 3781 3782 3783 3784 3785 3786 3787 3788 3789 3790 3791 3792 3793 3794 3795 3796 3797 3798 3799 3800 3801 3802 3803 3804 3805 3806 3807 3808 3809 3810 3811 3812 3813 3814 3815 3816 3817 3818 3819 3820 3821 3822 3823 3824 3825 3826 3827 3828 3829 3830 3831 3832 3833 3834 3835 3836 3837 3838 3839 3840 3841 3842 3843 3844 3845 3846 3847 3848 3849 3850 3851 3852 3853 3854 3855 3856 3857 3858 3859 3860 3861 3862 3863 3864 3865 3866 3867 3868 3869 3870 3871 3872 3873 3874 3875 3876 3877 3878 3879 3880 3881 3882 3883 3884 3885 3886 3887 3888 3889 3890 3891 3892 3893 3894 3895 3896 3897 3898 3899 3900 3901 3902 3903 3904 3905 3906 3907 3908 3909 3910 3911 3912 3913 3914 3915 3916 3917 3918 3919 3920 3921 3922 3923 3924 3925 3926 3927 3928 3929 3930 3931 3932 3933 3934 3935 3936 3937 3938 3939 3940 3941 3942 3943 3944 3945 3946 3947 3948 3949 3950 3951 3952 3953 3954 3955 3956 3957 3958 3959 3960 3961 3962 3963 3964 3965 3966 3967 3968 3969 3970 3971 3972 3973 3974 3975 3976 3977 3978 3979 3980 3981 3982 3983 3984 3985 3986 3987 3988 3989 3990 3991 3992 3993 3994 3995 3996 3997 3998 3999 4000 4001 4002 4003 4004 4005 4006 4007 4008 4009 4010 4011 4012 4013 4014 4015 4016 4017 4018 4019 4020 4021 4022 4023 4024 4025 4026 4027 4028 4029 4030 4031 4032 4033 4034 4035 4036 4037 4038 4039 4040 4041 4042 4043 4044 4045 4046 4047 4048 4049 4050 4051 4052 4053 4054 4055 4056 4057 4058 4059 4060 4061 4062 4063 4064 4065 4066 4067 4068 4069 4070 4071 4072 4073 4074 4075 4076 4077 4078 4079 4080 4081 4082 4083 4084 4085 4086 4087 4088 4089 4090 4091 4092 4093 4094 4095 4096 4097 4098 4099 4100 4101 4102 4103 4104 4105 4106 4107 4108 4109 4110 4111 4112 4113 4114 4115 4116 4117 4118 4119 4120 4121 4122 4123 4124 4125 4126 4127 4128 4129 4130 4131 4132 4133 4134 4135 4136 4137 4138 4139 4140 4141 4142 4143 4144 4145 4146 4147 4148 4149 4150 4151 4152 4153 4154 4155 4156 4157 4158 4159 4160 4161 4162 4163 4164 4165 4166 4167 4168 4169 4170 4171 4172 4173 4174 4175 4176 4177 4178 4179 4180 4181 4182 4183 4184 4185 4186 4187 4188 4189 4190 4191 4192 4193 4194 4195 4196 4197 4198 4199 4200 4201 4202 4203 4204 4205 4206 4207 4208 4209 4210 4211 4212 4213 4214 4215 4216 4217 4218 4219 4220 4221 4222 4223 4224 4225 4226 4227 4228 4229 4230 4231 4232 4233 4234 4235 4236 4237 4238 4239 4240 4241 4242 4243 4244 4245 4246 4247 4248 4249 4250 4251 4252 4253 4254 4255 4256 4257 4258 4259 4260 4261 4262 4263 4264 4265 4266 4267 4268 4269 4270 4271 4272 4273 4274 4275 4276 4277 4278 4279 4280 4281 4282 4283 4284 4285 4286 4287 4288 4289 4290 4291 4292 4293 4294 4295 4296 4297 4298 4299 4300 4301 4302 4303 4304 4305 4306 4307 4308 4309 4310 4311 4312 4313 4314 4315 4316 4317 4318 4319 4320 4321 4322 4323 4324 4325 4326 4327 4328 4329 4330 4331 4332 4333 4334 4335 4336 4337 4338 4339 4340 4341 4342 4343 4344 4345 4346 4347 4348 4349 4350 4351 4352 4353 4354 4355 4356 4357 4358 4359 4360 4361 4362 4363 4364 4365 4366 4367 4368 4369 4370 4371 4372 4373 4374 4375 4376 4377 4378 4379 4380 4381 4382 4383 4384 4385 4386 4387 4388 4389 4390 4391 4392 4393 4394 4395 4396 4397 4398 4399 4400 4401 4402 4403 4404 4405 4406 4407 4408 4409 4410 4411 4412 4413 4414 4415 4416 4417 4418 4419 4420 4421 4422 4423 4424 4425 4426 4427 4428 4429 4430 4431 4432 4433 4434 4435 4436 4437 4438 4439 4440 4441 4442 4443 4444 4445 4446 4447 4448 4449 4450 4451 4452 4453 4454 4455 4456 4457 4458 4459 4460 4461 4462 4463 4464 4465 4466 4467 4468 4469 4470 4471 4472 4473 4474 4475 4476 4477 4478 4479 4480 4481 4482 4483 4484 4485 4486 4487 4488 4489 4490 4491 4492 4493 4494 4495 4496 4497 4498 4499 4500 4501 4502 4503 4504 4505 4506 4507 4508 4509 4510 4511 4512 4513 4514 4515 4516 4517 4518 4519 4520 4521 4522 4523 4524 4525 4526 4527 4528 4529 4530 4531 4532 4533 4534 4535 4536 4537 4538 4539 4540 4541 4542 4543 4544 4545 4546 4547 4548 4549 4550 4551 4552 4553 4554 4555 4556 4557 4558 4559 4560 4561 4562 4563 4564 4565 4566 4567 4568 4569 4570 4571 4572 4573 4574 4575 4576 4577 4578 4579 4580 4581 4582 4583 4584 4585 4586 4587 4588 4589 4590 4591 4592 4593 4594 4595 4596 4597 4598 4599 4600 4601 4602 4603 4604 4605 4606 4607 4608 4609 4610 4611 4612 4613 4614 4615 4616 4617 4618 4619 4620 4621 4622 4623 4624 4625 4626 4627 4628 4629 4630 4631 4632 4633 4634 4635 4636 4637 4638 4639 4640 4641 4642 4643 4644 4645 4646 4647 4648 4649 4650 4651 4652 4653 4654 4655 4656 4657 4658 4659 4660 4661 4662 4663 4664 4665 4666 4667 4668 4669 4670 4671 4672 4673 4674 4675 4676 4677 4678 4679 4680 4681 4682 4683 4684 4685 4686 4687 4688 4689 4690 4691 4692 4693 4694 4695 4696 4697 4698 4699 4700 4701 4702 4703 4704 4705 4706 4707 4708 4709 4710 4711 4712 4713 4714 4715 4716 4717 4718 4719 4720 4721 4722 4723 4724 4725 4726 4727 4728 4729 4730 4731 4732 4733 4734 4735 4736 4737 4738 4739 4740 4741 4742 4743 4744 4745 4746 4747 4748 4749 4750 4751 4752 4753 4754 4755 4756 4757 4758 4759 4760 4761 4762 4763 4764 4765 4766 4767 4768 4769 4770 4771 4772 4773 4774 4775 4776 4777 4778 4779 4780 4781 4782 4783 4784 4785 4786 4787 4788 4789 4790 4791 4792 4793 4794 4795 4796 4797 4798 4799 4800 4801 4802 4803 4804 4805 4806 4807 4808 4809 4810 4811 4812 4813 4814 4815 4816 4817 4818 4819 4820 4821 4822 4823 4824 4825 4826 4827 4828 4829 4830 4831 4832 4833 4834 4835 4836 4837 4838 4839 4840 4841 4842 4843 4844 4845 4846 4847 4848 4849 4850 4851 4852 4853 4854 4855 4856 4857 4858 4859 4860 4861 4862 4863 4864 4865 4866 4867 4868 4869 4870 4871 4872 4873 4874 4875 4876 4877 4878 4879 4880 4881 4882 4883 4884 4885 4886 4887 4888 4889 4890 4891 4892 4893 4894 4895 4896 4897 4898 4899 4900 4901 4902 4903 4904 4905 | ..
AUTOGENERATED: DO NOT EDIT MANUALLY
.. _Parseandcompile:
Parse and compile
^^^^^^^^^^^^^^^^^
The key function here is :ref:`mj_loadXML`. It invokes the built-in parser and compiler, and either returns a pointer to
a valid mjModel, or NULL - in which case the user should check the error information in the user-provided string.
The model and all files referenced in it can be loaded from disk or from a VFS when provided.
.. _mj_loadXML:
`mj_loadXML <#mj_loadXML>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_loadXML
Parse XML file in MJCF or URDF format, compile it, return low-level model.
If vfs is not NULL, look up files in vfs before reading from disk.
If error is not NULL, it must have size error_sz.
.. _mj_parseXML:
`mj_parseXML <#mj_parseXML>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_parseXML
Parse spec from XML file.
.. _mj_parseXMLString:
`mj_parseXMLString <#mj_parseXMLString>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_parseXMLString
Parse spec from XML string.
.. _mj_compile:
`mj_compile <#mj_compile>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_compile
Compile :ref:`mjSpec` to :ref:`mjModel`. A spec can be edited and compiled multiple times, returning a new
:ref:`mjModel` instance that takes the edits into account.
If compilation fails, :ref:`mj_compile` returns ``NULL``; the error can be read with :ref:`mjs_getError`.
.. _mj_copyBack:
`mj_copyBack <#mj_copyBack>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_copyBack
Copy real-valued arrays from model to spec, returns 1 on success.
.. _mj_recompile:
`mj_recompile <#mj_recompile>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_recompile
Recompile spec to model, preserving the state. Like :ref:`mj_compile`, this function compiles an :ref:`mjSpec` to an
:ref:`mjModel`, with two differences. First, rather than returning an entirely new model, it will
reallocate existing :ref:`mjModel` and :ref:`mjData` instances in-place. Second, it will preserve the
:ref:`integration state<geIntegrationState>`, as given in the provided :ref:`mjData` instance, while accounting for
newly added or removed degrees of freedom. This allows the user to continue simulation with the same model and data
struct pointers while editing the model programmatically.
:ref:`mj_recompile` returns 0 if compilation succeed. In the case of failure, the given :ref:`mjModel` and :ref:`mjData`
instances will be deleted; as in :ref:`mj_compile`, the compilation error can be read with :ref:`mjs_getError`.
.. _mj_saveLastXML:
`mj_saveLastXML <#mj_saveLastXML>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_saveLastXML
Update XML data structures with info from low-level model created with :ref:`mj_loadXML`, save as MJCF.
If error is not NULL, it must have size error_sz.
Note that this function only saves models that have been loaded with :ref:`mj_loadXML`, the legacy loading mechanism.
See the :ref:`model editing<meOverview>` chapter to understand the difference between the old and new model loading and
saving mechanisms.
.. _mj_freeLastXML:
`mj_freeLastXML <#mj_freeLastXML>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_freeLastXML
Free last XML model if loaded. Called internally at each load.
.. _mj_saveXMLString:
`mj_saveXMLString <#mj_saveXMLString>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_saveXMLString
Save spec to XML string, return 0 on success, -1 on failure. If the length of the output buffer is too small, returns
the required size. XML saving automatically compiles the spec before saving.
.. _mj_saveXML:
`mj_saveXML <#mj_saveXML>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_saveXML
Save spec to XML file, return 0 on success, -1 otherwise. XML saving requires that the spec first be compiled.
.. _Mainsimulation:
Main simulation
^^^^^^^^^^^^^^^
These are the main entry points to the simulator. Most users will only need to call :ref:`mj_step`, which computes
everything and advanced the simulation state by one time step. Controls and applied forces must either be set in advance
(in ``mjData.{ctrl, qfrc_applied, xfrc_applied}``), or a control callback :ref:`mjcb_control` must be installed which
will be called just before the controls and applied forces are needed. Alternatively, one can use :ref:`mj_step1` and
:ref:`mj_step2` which break down the simulation pipeline into computations that are executed before and after the
controls are needed; in this way one can set controls that depend on the results from :ref:`mj_step1`. Keep in mind
though that the RK4 solver does not work with mj_step1/2. See :ref:`Pipeline` for a more detailed description.
mj_forward performs the same computations as :ref:`mj_step` but without the integration. It is useful after loading or
resetting a model (to put the entire mjData in a valid state), and also for out-of-order computations that involve
sampling or finite-difference approximations.
:ref:`mj_inverse` runs the inverse dynamics, and writes its output in ``mjData.qfrc_inverse``. Note that ``mjData.qacc``
must be set before calling this function. Given the state (qpos, qvel, act), mj_forward maps from force to acceleration,
while mj_inverse maps from acceleration to force. Mathematically these functions are inverse of each other, but
numerically this may not always be the case because the forward dynamics rely on a constraint optimization algorithm
which is usually terminated early. The difference between the results of forward and inverse dynamics can be computed
with the function :ref:`mj_compareFwdInv`, which can be thought of as another solver accuracy check (as well as a
general sanity check).
The skip version of :ref:`mj_forward` and :ref:`mj_inverse` are useful for example when qpos was unchanged but qvel was
changed (usually in the context of finite differencing). Then there is no point repeating the computations that only
depend on qpos. Calling the dynamics with skipstage = :ref:`mjSTAGE_POS<mjtStage>` will achieve these savings.
.. _mj_step:
`mj_step <#mj_step>`__
~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_step
Advance simulation, use control callback to obtain external force and control.
.. _mj_step1:
`mj_step1 <#mj_step1>`__
~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_step1
Advance simulation in two steps: before external force and control is set by user.
.. _mj_step2:
`mj_step2 <#mj_step2>`__
~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_step2
Advance simulation in two steps: after external force and control is set by user.
.. _mj_forward:
`mj_forward <#mj_forward>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_forward
Forward dynamics: same as mj_step but do not integrate in time.
.. _mj_inverse:
`mj_inverse <#mj_inverse>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_inverse
Inverse dynamics: qacc must be set before calling.
.. _mj_forwardSkip:
`mj_forwardSkip <#mj_forwardSkip>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_forwardSkip
Forward dynamics with skip; skipstage is mjtStage.
.. _mj_inverseSkip:
`mj_inverseSkip <#mj_inverseSkip>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_inverseSkip
Inverse dynamics with skip; skipstage is mjtStage.
.. _Support:
Support
^^^^^^^
These are support functions that need access to :ref:`mjModel` and :ref:`mjData`, unlike the utility functions which do
not need such access. Support functions are called within the simulator but some of them can also be useful for custom
computations, and are documented in more detail below.
.. _mj_stateSize:
`mj_stateSize <#mj_stateSize>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_stateSize
Returns the number of :ref:`mjtNum` |-| s required for a given state specification. The bits of the integer ``spec``
correspond to element fields of :ref:`mjtState`.
.. _mj_getState:
`mj_getState <#mj_getState>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_getState
Copy concatenated state components specified by ``spec`` from ``d`` into ``state``. The bits of the integer
``spec`` correspond to element fields of :ref:`mjtState`. Fails with :ref:`mju_error` if ``spec`` is invalid.
.. _mj_setState:
`mj_setState <#mj_setState>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_setState
Copy concatenated state components specified by ``spec`` from ``state`` into ``d``. The bits of the integer
``spec`` correspond to element fields of :ref:`mjtState`. Fails with :ref:`mju_error` if ``spec`` is invalid.
.. _mj_setKeyframe:
`mj_setKeyframe <#mj_setKeyframe>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_setKeyframe
Copy current state to the k-th model keyframe.
.. _mj_addContact:
`mj_addContact <#mj_addContact>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_addContact
Add contact to d->contact list; return 0 if success; 1 if buffer full.
.. _mj_isPyramidal:
`mj_isPyramidal <#mj_isPyramidal>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_isPyramidal
Determine type of friction cone.
.. _mj_isSparse:
`mj_isSparse <#mj_isSparse>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_isSparse
Determine type of constraint Jacobian.
.. _mj_isDual:
`mj_isDual <#mj_isDual>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_isDual
Determine type of solver (PGS is dual, CG and Newton are primal).
.. _mj_mulJacVec:
`mj_mulJacVec <#mj_mulJacVec>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_mulJacVec
This function multiplies the constraint Jacobian mjData.efc_J by a vector. Note that the Jacobian can be either dense or
sparse; the function is aware of this setting. Multiplication by J maps velocities from joint space to constraint space.
.. _mj_mulJacTVec:
`mj_mulJacTVec <#mj_mulJacTVec>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_mulJacTVec
Same as mj_mulJacVec but multiplies by the transpose of the Jacobian. This maps forces from constraint space to joint
space.
.. _mj_jac:
`mj_jac <#mj_jac>`__
~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_jac
This function computes an end-effector kinematic Jacobian, describing the local linear relationship between the
degrees-of-freedom and a given point. Given a body specified by its integer id (``body``) and a 3D point in the world
frame (``point``) treated as attached to the body, the Jacobian has both translational (``jacp``) and rotational
(``jacr``) components. Passing ``NULL`` for either pointer will skip that part of the computation. Each component is a
3-by-nv matrix. Each row of this matrix is the gradient of the corresponding coordinate of the specified point with
respect to the degrees-of-freedom. The frame with respect to which the Jacobian is computed is centered at the body
center-of-mass but aligned with the world frame. The minimal :ref:`pipeline stages<piForward>` required for Jacobian
computations to be consistent with the current generalized positions ``mjData.qpos`` are :ref:`mj_kinematics` followed
by :ref:`mj_comPos`.
.. _mj_jacBody:
`mj_jacBody <#mj_jacBody>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_jacBody
This and the remaining variants of the Jacobian function call mj_jac internally, with the center of the body, geom or
site. They are just shortcuts; the same can be achieved by calling mj_jac directly.
.. _mj_jacBodyCom:
`mj_jacBodyCom <#mj_jacBodyCom>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_jacBodyCom
Compute body center-of-mass end-effector Jacobian.
.. _mj_jacSubtreeCom:
`mj_jacSubtreeCom <#mj_jacSubtreeCom>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_jacSubtreeCom
Compute subtree center-of-mass end-effector Jacobian.
.. _mj_jacGeom:
`mj_jacGeom <#mj_jacGeom>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_jacGeom
Compute geom end-effector Jacobian.
.. _mj_jacSite:
`mj_jacSite <#mj_jacSite>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_jacSite
Compute site end-effector Jacobian.
.. _mj_jacPointAxis:
`mj_jacPointAxis <#mj_jacPointAxis>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_jacPointAxis
Compute translation end-effector Jacobian of point, and rotation Jacobian of axis.
.. _mj_jacDot:
`mj_jacDot <#mj_jacDot>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_jacDot
This function computes the time-derivative of an end-effector kinematic Jacobian computed by :ref:`mj_jac`.
The minimal :ref:`pipeline stages<piStages>` required for computation to be
consistent with the current generalized positions and velocities ``mjData.{qpos, qvel}`` are
:ref:`mj_kinematics`, :ref:`mj_comPos`, :ref:`mj_comVel` (in that order).
.. _mj_angmomMat:
`mj_angmomMat <#mj_angmomMat>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_angmomMat
This function computes the ``3 x nv`` angular momentum matrix :math:`H(q)`, providing the linear mapping from
generalized velocities to subtree angular momentum. More precisely if :math:`h` is the subtree angular momentum of
body index ``body`` in ``mjData.subtree_angmom`` (reported by the :ref:`subtreeangmom<sensor-subtreeangmom>` sensor)
and :math:`\dot q` is the generalized velocity ``mjData.qvel``, then :math:`h = H \dot q`.
.. _mj_name2id:
`mj_name2id <#mj_name2id>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_name2id
Get id of object with the specified :ref:`mjtObj` type and name, returns -1 if id not found.
.. _mj_id2name:
`mj_id2name <#mj_id2name>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_id2name
Get name of object with the specified :ref:`mjtObj` type and id, returns ``NULL`` if name not found.
.. _mj_fullM:
`mj_fullM <#mj_fullM>`__
~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_fullM
Convert sparse inertia matrix ``M`` into full (i.e. dense) matrix.
|br| ``dst`` must be of size ``nv x nv``, ``M`` must be of the same size as ``mjData.qM``.
.. _mj_mulM:
`mj_mulM <#mj_mulM>`__
~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_mulM
This function multiplies the joint-space inertia matrix stored in mjData.qM by a vector. qM has a custom sparse format
that the user should not attempt to manipulate directly. Alternatively one can convert qM to a dense matrix with
mj_fullM and then user regular matrix-vector multiplication, but this is slower because it no longer benefits from
sparsity.
.. _mj_mulM2:
`mj_mulM2 <#mj_mulM2>`__
~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_mulM2
Multiply vector by (inertia matrix)^(1/2).
.. _mj_addM:
`mj_addM <#mj_addM>`__
~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_addM
Add inertia matrix to destination matrix.
Destination can be sparse or dense when all int* are NULL.
.. _mj_applyFT:
`mj_applyFT <#mj_applyFT>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_applyFT
This function can be used to apply a Cartesian force and torque to a point on a body, and add the result to the vector
mjData.qfrc_applied of all applied forces. Note that the function requires a pointer to this vector, because sometimes
we want to add the result to a different vector.
.. _mj_objectVelocity:
`mj_objectVelocity <#mj_objectVelocity>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_objectVelocity
Compute object 6D velocity (rot:lin) in object-centered frame, world/local orientation.
.. _mj_objectAcceleration:
`mj_objectAcceleration <#mj_objectAcceleration>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_objectAcceleration
Compute object 6D acceleration (rot:lin) in object-centered frame, world/local orientation. If acceleration or force
sensors are not present in the model, :ref:`mj_rnePostConstraint` must be manually called in order to calculate
mjData.cacc -- the total body acceleration, including contributions from the constraint solver.
.. _mj_geomDistance:
`mj_geomDistance <#mj_geomDistance>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_geomDistance
Returns the smallest signed distance between two geoms and optionally the segment from ``geom1`` to ``geom2``.
Returned distances are bounded from above by ``distmax``. |br| If no collision of distance smaller than ``distmax`` is
found, the function will return ``distmax`` and ``fromto``, if given, will be set to (0, 0, 0, 0, 0, 0).
.. admonition:: different (correct) behavior under `nativeccd`
:class: note
As explained in :ref:`Collision Detection<coDistance>`, distances are inaccurate when using the
:ref:`legacy CCD pipeline<coCCD>`, and its use is discouraged.
.. _mj_contactForce:
`mj_contactForce <#mj_contactForce>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_contactForce
Extract 6D force:torque given contact id, in the contact frame.
.. _mj_differentiatePos:
`mj_differentiatePos <#mj_differentiatePos>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_differentiatePos
This function subtracts two vectors in the format of qpos (and divides the result by dt), while respecting the
properties of quaternions. Recall that unit quaternions represent spatial orientations. They are points on the unit
sphere in 4D. The tangent to that sphere is a 3D plane of rotational velocities. Thus when we subtract two quaternions
in the right way, the result is a 3D vector and not a 4D vector. Thus the output qvel has dimensionality nv while the
inputs have dimensionality nq.
.. _mj_integratePos:
`mj_integratePos <#mj_integratePos>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_integratePos
This is the opposite of mj_differentiatePos. It adds a vector in the format of qvel (scaled by dt) to a vector in the
format of qpos.
.. _mj_normalizeQuat:
`mj_normalizeQuat <#mj_normalizeQuat>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_normalizeQuat
Normalize all quaternions in qpos-type vector.
.. _mj_local2Global:
`mj_local2Global <#mj_local2Global>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_local2Global
Map from body local to global Cartesian coordinates, sameframe takes values from mjtSameFrame.
.. _mj_getTotalmass:
`mj_getTotalmass <#mj_getTotalmass>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_getTotalmass
Sum all body masses.
.. _mj_setTotalmass:
`mj_setTotalmass <#mj_setTotalmass>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_setTotalmass
Scale body masses and inertias to achieve specified total mass.
.. _mj_getPluginConfig:
`mj_getPluginConfig <#mj_getPluginConfig>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_getPluginConfig
Return a config attribute value of a plugin instance;
NULL: invalid plugin instance ID or attribute name
.. _mj_loadPluginLibrary:
`mj_loadPluginLibrary <#mj_loadPluginLibrary>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_loadPluginLibrary
Load a dynamic library. The dynamic library is assumed to register one or more plugins.
.. _mj_loadAllPluginLibraries:
`mj_loadAllPluginLibraries <#mj_loadAllPluginLibraries>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_loadAllPluginLibraries
Scan a directory and load all dynamic libraries. Dynamic libraries in the specified directory
are assumed to register one or more plugins. Optionally, if a callback is specified, it is called
for each dynamic library encountered that registers plugins.
.. _mj_version:
`mj_version <#mj_version>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_version
Return version number: 1.0.2 is encoded as 102.
.. _mj_versionString:
`mj_versionString <#mj_versionString>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_versionString
Return the current version of MuJoCo as a null-terminated string.
.. _Components:
Components
^^^^^^^^^^
These are components of the simulation pipeline, called internally from :ref:`mj_step`, :ref:`mj_forward` and
:ref:`mj_inverse`. It is unlikely that the user will need to call them.
.. _mj_fwdPosition:
`mj_fwdPosition <#mj_fwdPosition>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_fwdPosition
Run position-dependent computations.
.. _mj_fwdVelocity:
`mj_fwdVelocity <#mj_fwdVelocity>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_fwdVelocity
Run velocity-dependent computations.
.. _mj_fwdActuation:
`mj_fwdActuation <#mj_fwdActuation>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_fwdActuation
Compute actuator force qfrc_actuator.
.. _mj_fwdAcceleration:
`mj_fwdAcceleration <#mj_fwdAcceleration>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_fwdAcceleration
Add up all non-constraint forces, compute qacc_smooth.
.. _mj_fwdConstraint:
`mj_fwdConstraint <#mj_fwdConstraint>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_fwdConstraint
Run selected constraint solver.
.. _mj_Euler:
`mj_Euler <#mj_Euler>`__
~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_Euler
Euler integrator, semi-implicit in velocity.
.. _mj_RungeKutta:
`mj_RungeKutta <#mj_RungeKutta>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_RungeKutta
Runge-Kutta explicit order-N integrator.
.. _mj_implicit:
`mj_implicit <#mj_implicit>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_implicit
Integrates the simulation state using an implicit-in-velocity integrator (either "implicit" or "implicitfast", see
:ref:`Numerical Integration<geIntegration>`), and advances simulation time. See `mjdata.h
<https://github.com/google-deepmind/mujoco/blob/main/include/mujoco/mjdata.h>`__ for fields computed by this function.
.. _mj_invPosition:
`mj_invPosition <#mj_invPosition>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_invPosition
Run position-dependent computations in inverse dynamics.
.. _mj_invVelocity:
`mj_invVelocity <#mj_invVelocity>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_invVelocity
Run velocity-dependent computations in inverse dynamics.
.. _mj_invConstraint:
`mj_invConstraint <#mj_invConstraint>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_invConstraint
Apply the analytical formula for inverse constraint dynamics.
.. _mj_compareFwdInv:
`mj_compareFwdInv <#mj_compareFwdInv>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_compareFwdInv
Compare forward and inverse dynamics, save results in fwdinv.
.. _Subcomponents:
Sub components
^^^^^^^^^^^^^^
These are sub-components of the simulation pipeline, called internally from the components above.
.. _mj_sensorPos:
`mj_sensorPos <#mj_sensorPos>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_sensorPos
Evaluate position-dependent sensors.
.. _mj_sensorVel:
`mj_sensorVel <#mj_sensorVel>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_sensorVel
Evaluate velocity-dependent sensors.
.. _mj_sensorAcc:
`mj_sensorAcc <#mj_sensorAcc>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_sensorAcc
Evaluate acceleration and force-dependent sensors.
.. _mj_energyPos:
`mj_energyPos <#mj_energyPos>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_energyPos
Evaluate position-dependent energy (potential).
.. _mj_energyVel:
`mj_energyVel <#mj_energyVel>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_energyVel
Evaluate velocity-dependent energy (kinetic).
.. _mj_checkPos:
`mj_checkPos <#mj_checkPos>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_checkPos
Check qpos, reset if any element is too big or nan.
.. _mj_checkVel:
`mj_checkVel <#mj_checkVel>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_checkVel
Check qvel, reset if any element is too big or nan.
.. _mj_checkAcc:
`mj_checkAcc <#mj_checkAcc>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_checkAcc
Check qacc, reset if any element is too big or nan.
.. _mj_kinematics:
`mj_kinematics <#mj_kinematics>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_kinematics
Run forward kinematics.
.. _mj_comPos:
`mj_comPos <#mj_comPos>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_comPos
Map inertias and motion dofs to global frame centered at CoM.
.. _mj_camlight:
`mj_camlight <#mj_camlight>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_camlight
Compute camera and light positions and orientations.
.. _mj_flex:
`mj_flex <#mj_flex>`__
~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_flex
Compute flex-related quantities.
.. _mj_tendon:
`mj_tendon <#mj_tendon>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_tendon
Compute tendon lengths, velocities and moment arms.
.. _mj_transmission:
`mj_transmission <#mj_transmission>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_transmission
Compute actuator transmission lengths and moments.
.. _mj_crb:
`mj_crb <#mj_crb>`__
~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_crb
Run composite rigid body inertia algorithm (CRB).
.. _mj_makeM:
`mj_makeM <#mj_makeM>`__
~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_makeM
Compute the composite rigid body inertia with :ref:`mj_crb`, add terms due
to :ref:`tendon armature<tendon-spatial-armature>`. The joint-space inertia matrix is stored in both ``mjData.qM`` and
``mjData.M``. These arrays represent the same quantity using different layouts (parent-based and compressed sparse row,
respectively).
.. _mj_factorM:
`mj_factorM <#mj_factorM>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_factorM
Compute sparse :math:`L^T D L` factorizaton of inertia matrix.
.. _mj_solveM:
`mj_solveM <#mj_solveM>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_solveM
Solve linear system :math:`M x = y` using factorization: :math:`x = (L^T D L)^{-1} y`
.. _mj_solveM2:
`mj_solveM2 <#mj_solveM2>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_solveM2
Half of linear solve: :math:`x = \sqrt{D^{-1}} (L^T)^{-1} y`
.. _mj_comVel:
`mj_comVel <#mj_comVel>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_comVel
Compute cvel, cdof_dot.
.. _mj_passive:
`mj_passive <#mj_passive>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_passive
Compute qfrc_passive from spring-dampers, gravity compensation and fluid forces.
.. _mj_subtreeVel:
`mj_subtreeVel <#mj_subtreeVel>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_subtreeVel
Sub-tree linear velocity and angular momentum: compute ``subtree_linvel``, ``subtree_angmom``.
This function is triggered automatically if the subtree :ref:`velocity<sensor-subtreelinvel>` or
:ref:`momentum<sensor-subtreeangmom>` sensors are present in the model.
It is also triggered for :ref:`user sensors<sensor-user>` of :ref:`stage<sensor-user-needstage>` "vel".
.. _mj_rne:
`mj_rne <#mj_rne>`__
~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_rne
Recursive Newton Euler: compute :math:`M(q) \ddot q + C(q,\dot q)`. ``flg_acc=0`` removes the inertial term (i.e.
assumes :math:`\ddot q = 0`).
.. _mj_rnePostConstraint:
`mj_rnePostConstraint <#mj_rnePostConstraint>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_rnePostConstraint
Recursive Newton Euler with final computed forces and accelerations.
Computes three body-level ``nv x 6`` arrays, all defined in the subtreecom-based
:ref:`c-frame<tyNotesCom>` and arranged in ``[rotation(3), translation(3)]`` order.
- ``cacc``: Body acceleration, required for :ref:`mj_objectAcceleration`.
- ``cfrc_int``: Interaction force with the parent body.
- ``cfrc_ext``: External force acting on the body.
This function is triggered automatically if the following sensors are present in the model:
:ref:`accelerometer<sensor-accelerometer>`, :ref:`force<sensor-force>`, :ref:`torque<sensor-torque>`,
:ref:`framelinacc<sensor-framelinacc>`, :ref:`frameangacc<sensor-frameangacc>`.
It is also triggered for :ref:`user sensors<sensor-user>` of :ref:`stage<sensor-user-needstage>` "acc".
The computed force arrays ``cfrc_int`` and ``cfrc_ext`` currently suffer from a know bug, they do not take into account
the effect of spatial tendons, see :github:issue:`832`.
.. _mj_collision:
`mj_collision <#mj_collision>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_collision
Run collision detection.
.. _mj_makeConstraint:
`mj_makeConstraint <#mj_makeConstraint>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_makeConstraint
Construct constraints.
.. _mj_island:
`mj_island <#mj_island>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_island
Find constraint islands.
.. _mj_projectConstraint:
`mj_projectConstraint <#mj_projectConstraint>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_projectConstraint
Compute inverse constraint inertia efc_AR.
.. _mj_referenceConstraint:
`mj_referenceConstraint <#mj_referenceConstraint>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_referenceConstraint
Compute efc_vel, efc_aref.
.. _mj_constraintUpdate:
`mj_constraintUpdate <#mj_constraintUpdate>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_constraintUpdate
Compute ``efc_state``, ``efc_force``, ``qfrc_constraint``, and (optionally) cone Hessians.
If ``cost`` is not ``NULL``, set ``*cost = s(jar)`` where ``jar = Jac*qacc - aref``.
.. _Raycollisions:
Ray casting
^^^^^^^^^^^
Ray collisions, also known as ray casting, find the distance ``x`` of a ray's intersection with a geom, where a ray is
a line emanating from the 3D point ``p`` in the direction ``v`` i.e., ``(p + x*v, x >= 0)``. All functions in this
family return the distance to the nearest geom surface, or -1 if there is no intersection. Note that if ``p`` is inside
a geom, the ray will intersect the surface from the inside which still counts as an intersection.
All ray collision functions rely on quantities computed by :ref:`mj_kinematics` (see :ref:`mjData`), so must be called
after :ref:`mj_kinematics`, or functions that call it (e.g. :ref:`mj_fwdPosition`). The top level functions, which
intersect with all geoms types, are :ref:`mj_ray` which casts a single ray, and :ref:`mj_multiRay` which casts multiple
rays from a single point.
.. _mj_multiRay:
`mj_multiRay <#mj_multiRay>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_multiRay
Intersect multiple rays emanating from a single point.
Similar semantics to mj_ray, but vec is an array of (nray x 3) directions.
.. _mj_ray:
`mj_ray <#mj_ray>`__
~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_ray
Intersect ray ``(pnt+x*vec, x >= 0)`` with visible geoms, except geoms in bodyexclude.
Return geomid and distance (x) to nearest surface, or -1 if no intersection.
geomgroup is an array of length mjNGROUP, where 1 means the group should be included. Pass geomgroup=NULL to skip
group exclusion.
If flg_static is 0, static geoms will be excluded.
bodyexclude=-1 can be used to indicate that all bodies are included.
.. _mj_rayHfield:
`mj_rayHfield <#mj_rayHfield>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_rayHfield
Intersect ray with hfield, return nearest distance or -1 if no intersection.
.. _mj_rayMesh:
`mj_rayMesh <#mj_rayMesh>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_rayMesh
Intersect ray with mesh, return nearest distance or -1 if no intersection.
.. _mju_rayGeom:
`mju_rayGeom <#mju_rayGeom>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_rayGeom
Intersect ray with pure geom, return nearest distance or -1 if no intersection.
.. _mju_rayFlex:
`mju_rayFlex <#mju_rayFlex>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_rayFlex
Intersect ray with flex, return nearest distance or -1 if no intersection,
and also output nearest vertex id.
.. _mju_raySkin:
`mju_raySkin <#mju_raySkin>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_raySkin
Intersect ray with skin, return nearest distance or -1 if no intersection,
and also output nearest vertex id.
.. _Printing:
Printing
^^^^^^^^
These functions can be used to print various quantities to the screen for debugging purposes.
.. _mj_printFormattedModel:
`mj_printFormattedModel <#mj_printFormattedModel>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_printFormattedModel
Print mjModel to text file, specifying format.
float_format must be a valid printf-style format string for a single float value.
.. _mj_printModel:
`mj_printModel <#mj_printModel>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_printModel
Print model to text file.
.. _mj_printFormattedData:
`mj_printFormattedData <#mj_printFormattedData>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_printFormattedData
Print mjData to text file, specifying format.
float_format must be a valid printf-style format string for a single float value
.. _mj_printData:
`mj_printData <#mj_printData>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_printData
Print data to text file.
.. _mju_printMat:
`mju_printMat <#mju_printMat>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_printMat
Print matrix to screen.
.. _mju_printMatSparse:
`mju_printMatSparse <#mju_printMatSparse>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_printMatSparse
Print sparse matrix to screen.
.. _mj_printSchema:
`mj_printSchema <#mj_printSchema>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_printSchema
Print internal XML schema as plain text or HTML, with style-padding or `` ``.
.. _Virtualfilesystem:
Virtual file system
^^^^^^^^^^^^^^^^^^^
Virtual file system (VFS) enables the user to load all necessary files in memory, including MJB binary model files, XML
files (MJCF, URDF and included files), STL meshes, PNGs for textures and height fields, and HF files in our custom
height field format. Model and resource files in the VFS can also be constructed programmatically (say using a Python
library that writes to memory). Once all desired files are in the VFS, the user can call :ref:`mj_loadModel` or
:ref:`mj_loadXML` with a pointer to the VFS. When this pointer is not NULL, the loaders will first check the VFS for any
files they are about to load, and only access the disk if the file is not found in the VFS.
The VFS must first be allocated using :ref:`mj_defaultVFS` and must be freed with :ref:`mj_deleteVFS`.
.. _mj_defaultVFS:
`mj_defaultVFS <#mj_defaultVFS>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_defaultVFS
Initialize an empty VFS, :ref:`mj_deleteVFS` must be called to deallocate the VFS.
.. _mj_addFileVFS:
`mj_addFileVFS <#mj_addFileVFS>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_addFileVFS
Add file to VFS. The directory argument is optional and can be NULL or empty. Returns 0 on success,
2 on name collision, or -1 when an internal error occurs.
.. _mj_addBufferVFS:
`mj_addBufferVFS <#mj_addBufferVFS>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_addBufferVFS
Add file to VFS from buffer, return 0: success, 2: repeated name, -1: failed to load.
.. _mj_deleteFileVFS:
`mj_deleteFileVFS <#mj_deleteFileVFS>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_deleteFileVFS
Delete file from VFS, return 0: success, -1: not found in VFS.
.. _mj_deleteVFS:
`mj_deleteVFS <#mj_deleteVFS>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_deleteVFS
Delete all files from VFS and deallocates VFS internal memory.
.. _Initialization:
Initialization
^^^^^^^^^^^^^^
This section contains functions that load/initialize the model or other data structures. Their use is well illustrated
in the code samples.
.. _mj_defaultLROpt:
`mj_defaultLROpt <#mj_defaultLROpt>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_defaultLROpt
Set default options for length range computation.
.. _mj_defaultSolRefImp:
`mj_defaultSolRefImp <#mj_defaultSolRefImp>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_defaultSolRefImp
Set solver parameters to default values.
.. _mj_defaultOption:
`mj_defaultOption <#mj_defaultOption>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_defaultOption
Set physics options to default values.
.. _mj_defaultVisual:
`mj_defaultVisual <#mj_defaultVisual>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_defaultVisual
Set visual options to default values.
.. _mj_copyModel:
`mj_copyModel <#mj_copyModel>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_copyModel
Copy mjModel, allocate new if dest is NULL.
.. _mj_saveModel:
`mj_saveModel <#mj_saveModel>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_saveModel
Save model to binary MJB file or memory buffer; buffer has precedence when given.
.. _mj_loadModel:
`mj_loadModel <#mj_loadModel>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_loadModel
Load model from binary MJB file.
If vfs is not NULL, look up file in vfs before reading from disk.
.. _mj_deleteModel:
`mj_deleteModel <#mj_deleteModel>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_deleteModel
Free memory allocation in model.
.. _mj_sizeModel:
`mj_sizeModel <#mj_sizeModel>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_sizeModel
Return size of buffer needed to hold model.
.. _mj_makeData:
`mj_makeData <#mj_makeData>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_makeData
Allocate mjData corresponding to given model.
If the model buffer is unallocated the initial configuration will not be set.
.. _mj_copyData:
`mj_copyData <#mj_copyData>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_copyData
Copy mjData.
m is only required to contain the size fields from MJMODEL_INTS.
.. _mjv_copyData:
`mjv_copyData <#mjv_copyData>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjv_copyData
Copy mjData, skip large arrays not required for visualization.
.. _mj_resetData:
`mj_resetData <#mj_resetData>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_resetData
Reset data to defaults.
.. _mj_resetDataDebug:
`mj_resetDataDebug <#mj_resetDataDebug>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_resetDataDebug
Reset data to defaults, fill everything else with debug_value.
.. _mj_resetDataKeyframe:
`mj_resetDataKeyframe <#mj_resetDataKeyframe>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_resetDataKeyframe
Reset data. If 0 <= key < nkey, set fields from specified keyframe.
.. _mj_markStack:
`mj_markStack <#mj_markStack>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_markStack
Mark a new frame on the mjData stack.
.. _mj_freeStack:
`mj_freeStack <#mj_freeStack>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_freeStack
Free the current mjData stack frame. All pointers returned by mj_stackAlloc since the last call
to mj_markStack must no longer be used afterwards.
.. _mj_stackAllocByte:
`mj_stackAllocByte <#mj_stackAllocByte>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_stackAllocByte
Allocate a number of bytes on mjData stack at a specific alignment.
Call mju_error on stack overflow.
.. _mj_stackAllocNum:
`mj_stackAllocNum <#mj_stackAllocNum>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_stackAllocNum
Allocate array of mjtNums on mjData stack. Call mju_error on stack overflow.
.. _mj_stackAllocInt:
`mj_stackAllocInt <#mj_stackAllocInt>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_stackAllocInt
Allocate array of ints on mjData stack. Call mju_error on stack overflow.
.. _mj_deleteData:
`mj_deleteData <#mj_deleteData>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_deleteData
Free memory allocation in mjData.
.. _mj_resetCallbacks:
`mj_resetCallbacks <#mj_resetCallbacks>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_resetCallbacks
Reset all callbacks to NULL pointers (NULL is the default).
.. _mj_setConst:
`mj_setConst <#mj_setConst>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_setConst
Set constant fields of mjModel, corresponding to qpos0 configuration.
.. _mj_setLengthRange:
`mj_setLengthRange <#mj_setLengthRange>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_setLengthRange
Set actuator_lengthrange for specified actuator; return 1 if ok, 0 if error.
.. _mj_makeSpec:
`mj_makeSpec <#mj_makeSpec>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_makeSpec
Create empty spec.
.. _mj_copySpec:
`mj_copySpec <#mj_copySpec>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_copySpec
Copy spec.
.. _mj_deleteSpec:
`mj_deleteSpec <#mj_deleteSpec>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_deleteSpec
Free memory allocation in mjSpec.
.. _mjs_activatePlugin:
`mjs_activatePlugin <#mjs_activatePlugin>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_activatePlugin
Activate plugin. Returns 0 on success.
.. _mjs_setDeepCopy:
`mjs_setDeepCopy <#mjs_setDeepCopy>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_setDeepCopy
Turn deep copy on or off attach. Returns 0 on success.
.. _Errorandmemory:
Error and memory
^^^^^^^^^^^^^^^^
.. _mju_error:
`mju_error <#mju_error>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_error
Main error function; does not return to caller.
.. _mju_error_i:
`mju_error_i <#mju_error_i>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_error_i
Deprecated: use mju_error.
.. _mju_error_s:
`mju_error_s <#mju_error_s>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_error_s
Deprecated: use mju_error.
.. _mju_warning:
`mju_warning <#mju_warning>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_warning
Main warning function; returns to caller.
.. _mju_warning_i:
`mju_warning_i <#mju_warning_i>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_warning_i
Deprecated: use mju_warning.
.. _mju_warning_s:
`mju_warning_s <#mju_warning_s>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_warning_s
Deprecated: use mju_warning.
.. _mju_clearHandlers:
`mju_clearHandlers <#mju_clearHandlers>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_clearHandlers
Clear user error and memory handlers.
.. _mju_malloc:
`mju_malloc <#mju_malloc>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_malloc
Allocate memory; byte-align on 64; pad size to multiple of 64.
.. _mju_free:
`mju_free <#mju_free>`__
~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_free
Free memory, using free() by default.
.. _mj_warning:
`mj_warning <#mj_warning>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mj_warning
High-level warning function: count warnings in mjData, print only the first.
.. _mju_writeLog:
`mju_writeLog <#mju_writeLog>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_writeLog
Write [datetime, type: message] to MUJOCO_LOG.TXT.
.. _mjs_getError:
`mjs_getError <#mjs_getError>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_getError
Get compiler error message from spec.
.. _mjs_isWarning:
`mjs_isWarning <#mjs_isWarning>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_isWarning
Return 1 if compiler error is a warning.
.. _Miscellaneous:
Miscellaneous
^^^^^^^^^^^^^
.. _mju_muscleGain:
`mju_muscleGain <#mju_muscleGain>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_muscleGain
Muscle active force, prm = (range[2], force, scale, lmin, lmax, vmax, fpmax, fvmax).
.. _mju_muscleBias:
`mju_muscleBias <#mju_muscleBias>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_muscleBias
Muscle passive force, prm = (range[2], force, scale, lmin, lmax, vmax, fpmax, fvmax).
.. _mju_muscleDynamics:
`mju_muscleDynamics <#mju_muscleDynamics>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_muscleDynamics
Muscle activation dynamics, prm = (tau_act, tau_deact, smoothing_width).
.. _mju_encodePyramid:
`mju_encodePyramid <#mju_encodePyramid>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_encodePyramid
Convert contact force to pyramid representation.
.. _mju_decodePyramid:
`mju_decodePyramid <#mju_decodePyramid>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_decodePyramid
Convert pyramid representation to contact force.
.. _mju_springDamper:
`mju_springDamper <#mju_springDamper>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_springDamper
Integrate spring-damper analytically, return pos(dt).
.. _mju_min:
`mju_min <#mju_min>`__
~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_min
Return min(a,b) with single evaluation of a and b.
.. _mju_max:
`mju_max <#mju_max>`__
~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_max
Return max(a,b) with single evaluation of a and b.
.. _mju_clip:
`mju_clip <#mju_clip>`__
~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_clip
Clip x to the range [min, max].
.. _mju_sign:
`mju_sign <#mju_sign>`__
~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_sign
Return sign of x: +1, -1 or 0.
.. _mju_round:
`mju_round <#mju_round>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_round
Round x to nearest integer.
.. _mju_type2Str:
`mju_type2Str <#mju_type2Str>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_type2Str
Convert type id (mjtObj) to type name.
.. _mju_str2Type:
`mju_str2Type <#mju_str2Type>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_str2Type
Convert type name to type id (mjtObj).
.. _mju_writeNumBytes:
`mju_writeNumBytes <#mju_writeNumBytes>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_writeNumBytes
Return human readable number of bytes using standard letter suffix.
.. _mju_warningText:
`mju_warningText <#mju_warningText>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_warningText
Construct a warning message given the warning type and info.
.. _mju_isBad:
`mju_isBad <#mju_isBad>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_isBad
Return 1 if nan or abs(x)>mjMAXVAL, 0 otherwise. Used by check functions.
.. _mju_isZero:
`mju_isZero <#mju_isZero>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_isZero
Return 1 if all elements are 0.
.. _mju_standardNormal:
`mju_standardNormal <#mju_standardNormal>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_standardNormal
Standard normal random number generator (optional second number).
.. _mju_f2n:
`mju_f2n <#mju_f2n>`__
~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_f2n
Convert from float to mjtNum.
.. _mju_n2f:
`mju_n2f <#mju_n2f>`__
~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_n2f
Convert from mjtNum to float.
.. _mju_d2n:
`mju_d2n <#mju_d2n>`__
~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_d2n
Convert from double to mjtNum.
.. _mju_n2d:
`mju_n2d <#mju_n2d>`__
~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_n2d
Convert from mjtNum to double.
.. _mju_insertionSort:
`mju_insertionSort <#mju_insertionSort>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_insertionSort
Insertion sort, resulting list is in increasing order.
.. _mju_insertionSortInt:
`mju_insertionSortInt <#mju_insertionSortInt>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_insertionSortInt
Integer insertion sort, resulting list is in increasing order.
.. _mju_Halton:
`mju_Halton <#mju_Halton>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_Halton
Generate Halton sequence.
.. _mju_strncpy:
`mju_strncpy <#mju_strncpy>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_strncpy
Call strncpy, then set dst[n-1] = 0.
.. _mju_sigmoid:
`mju_sigmoid <#mju_sigmoid>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_sigmoid
Twice continuously differentiable sigmoid function using a quintic polynomial:
.. math::
s(x) =
\begin{cases}
0, & & x \le 0 \\
6x^5 - 15x^4 + 10x^3, & 0 \lt & x \lt 1 \\
1, & 1 \le & x \qquad
\end{cases}
.. _Interaction:
Interaction
^^^^^^^^^^^
These functions implement abstract mouse interactions, allowing control over cameras and perturbations. Their use is well
illustrated in :ref:`simulate<saSimulate>`.
.. _mjv_defaultCamera:
`mjv_defaultCamera <#mjv_defaultCamera>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjv_defaultCamera
Set default camera.
.. _mjv_defaultFreeCamera:
`mjv_defaultFreeCamera <#mjv_defaultFreeCamera>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjv_defaultFreeCamera
Set default free camera.
.. _mjv_defaultPerturb:
`mjv_defaultPerturb <#mjv_defaultPerturb>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjv_defaultPerturb
Set default perturbation.
.. _mjv_room2model:
`mjv_room2model <#mjv_room2model>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjv_room2model
Transform pose from room to model space.
.. _mjv_model2room:
`mjv_model2room <#mjv_model2room>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjv_model2room
Transform pose from model to room space.
.. _mjv_cameraInModel:
`mjv_cameraInModel <#mjv_cameraInModel>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjv_cameraInModel
Get camera info in model space; average left and right OpenGL cameras.
.. _mjv_cameraInRoom:
`mjv_cameraInRoom <#mjv_cameraInRoom>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjv_cameraInRoom
Get camera info in room space; average left and right OpenGL cameras.
.. _mjv_frustumHeight:
`mjv_frustumHeight <#mjv_frustumHeight>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjv_frustumHeight
Get frustum height at unit distance from camera; average left and right OpenGL cameras.
.. _mjv_alignToCamera:
`mjv_alignToCamera <#mjv_alignToCamera>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjv_alignToCamera
Rotate 3D vec in horizontal plane by angle between (0,1) and (forward_x,forward_y).
.. _mjv_moveCamera:
`mjv_moveCamera <#mjv_moveCamera>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjv_moveCamera
Move camera with mouse; action is mjtMouse.
.. _mjv_movePerturb:
`mjv_movePerturb <#mjv_movePerturb>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjv_movePerturb
Move perturb object with mouse; action is mjtMouse.
.. _mjv_moveModel:
`mjv_moveModel <#mjv_moveModel>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjv_moveModel
Move model with mouse; action is mjtMouse.
.. _mjv_initPerturb:
`mjv_initPerturb <#mjv_initPerturb>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjv_initPerturb
Copy perturb pos,quat from selected body; set scale for perturbation.
.. _mjv_applyPerturbPose:
`mjv_applyPerturbPose <#mjv_applyPerturbPose>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjv_applyPerturbPose
Set perturb pos,quat in d->mocap when selected body is mocap, and in d->qpos otherwise.
Write d->qpos only if flg_paused and subtree root for selected body has free joint.
.. _mjv_applyPerturbForce:
`mjv_applyPerturbForce <#mjv_applyPerturbForce>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjv_applyPerturbForce
Set perturb force,torque in d->xfrc_applied, if selected body is dynamic.
.. _mjv_averageCamera:
`mjv_averageCamera <#mjv_averageCamera>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjv_averageCamera
Return the average of two OpenGL cameras.
.. _mjv_select:
`mjv_select <#mjv_select>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjv_select
This function is used for mouse selection, relying on ray intersections. aspectratio is the viewport width/height. relx
and rely are the relative coordinates of the 2D point of interest in the viewport (usually mouse cursor). The function
returns the id of the geom under the specified 2D point, or -1 if there is no geom (note that they skybox if present is
not a model geom). The 3D coordinates of the clicked point are returned in selpnt. See :ref:`simulate<saSimulate>` for
an illustration.
.. _Visualization-api:
Visualization
^^^^^^^^^^^^^
The functions in this section implement abstract visualization. The results are used by the OpenGL renderer, and can
also be used by users wishing to implement their own renderer, or hook up MuJoCo to advanced rendering tools such as
Unity or Unreal Engine. See :ref:`simulate<saSimulate>` for illustration of how to use these functions.
.. _mjv_defaultOption:
`mjv_defaultOption <#mjv_defaultOption>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjv_defaultOption
Set default visualization options.
.. _mjv_defaultFigure:
`mjv_defaultFigure <#mjv_defaultFigure>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjv_defaultFigure
Set default figure.
.. _mjv_initGeom:
`mjv_initGeom <#mjv_initGeom>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjv_initGeom
Initialize given geom fields when not NULL, set the rest to their default values.
.. _mjv_connector:
`mjv_connector <#mjv_connector>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjv_connector
Set (type, size, pos, mat) for connector-type geom between given points.
Assume that mjv_initGeom was already called to set all other properties.
Width of mjGEOM_LINE is denominated in pixels.
.. _mjv_defaultScene:
`mjv_defaultScene <#mjv_defaultScene>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjv_defaultScene
Set default abstract scene.
.. _mjv_makeScene:
`mjv_makeScene <#mjv_makeScene>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjv_makeScene
Allocate resources in abstract scene.
.. _mjv_freeScene:
`mjv_freeScene <#mjv_freeScene>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjv_freeScene
Free abstract scene.
.. _mjv_updateScene:
`mjv_updateScene <#mjv_updateScene>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjv_updateScene
Update entire scene given model state.
.. _mjv_copyModel:
`mjv_copyModel <#mjv_copyModel>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjv_copyModel
Copy mjModel, skip large arrays not required for abstract visualization.
.. _mjv_addGeoms:
`mjv_addGeoms <#mjv_addGeoms>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjv_addGeoms
Add geoms from selected categories.
.. _mjv_makeLights:
`mjv_makeLights <#mjv_makeLights>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjv_makeLights
Make list of lights.
.. _mjv_updateCamera:
`mjv_updateCamera <#mjv_updateCamera>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjv_updateCamera
Update camera.
.. _mjv_updateSkin:
`mjv_updateSkin <#mjv_updateSkin>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjv_updateSkin
Update skins.
.. _OpenGLrendering:
OpenGL rendering
^^^^^^^^^^^^^^^^
These functions expose the OpenGL renderer. See :ref:`simulate<saSimulate>` for an illustration
of how to use these functions.
.. _mjr_defaultContext:
`mjr_defaultContext <#mjr_defaultContext>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjr_defaultContext
Set default mjrContext.
.. _mjr_makeContext:
`mjr_makeContext <#mjr_makeContext>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjr_makeContext
Allocate resources in custom OpenGL context; fontscale is mjtFontScale.
.. _mjr_changeFont:
`mjr_changeFont <#mjr_changeFont>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjr_changeFont
Change font of existing context.
.. _mjr_addAux:
`mjr_addAux <#mjr_addAux>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjr_addAux
Add Aux buffer with given index to context; free previous Aux buffer.
.. _mjr_freeContext:
`mjr_freeContext <#mjr_freeContext>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjr_freeContext
Free resources in custom OpenGL context, set to default.
.. _mjr_resizeOffscreen:
`mjr_resizeOffscreen <#mjr_resizeOffscreen>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjr_resizeOffscreen
Resize offscreen buffers.
.. _mjr_uploadTexture:
`mjr_uploadTexture <#mjr_uploadTexture>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjr_uploadTexture
Upload texture to GPU, overwriting previous upload if any.
.. _mjr_uploadMesh:
`mjr_uploadMesh <#mjr_uploadMesh>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjr_uploadMesh
Upload mesh to GPU, overwriting previous upload if any.
.. _mjr_uploadHField:
`mjr_uploadHField <#mjr_uploadHField>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjr_uploadHField
Upload height field to GPU, overwriting previous upload if any.
.. _mjr_restoreBuffer:
`mjr_restoreBuffer <#mjr_restoreBuffer>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjr_restoreBuffer
Make con->currentBuffer current again.
.. _mjr_setBuffer:
`mjr_setBuffer <#mjr_setBuffer>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjr_setBuffer
Set OpenGL framebuffer for rendering: mjFB_WINDOW or mjFB_OFFSCREEN.
If only one buffer is available, set that buffer and ignore framebuffer argument.
.. _mjr_readPixels:
`mjr_readPixels <#mjr_readPixels>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjr_readPixels
Read pixels from current OpenGL framebuffer to client buffer.
Viewport is in OpenGL framebuffer; client buffer starts at (0,0).
.. _mjr_drawPixels:
`mjr_drawPixels <#mjr_drawPixels>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjr_drawPixels
Draw pixels from client buffer to current OpenGL framebuffer.
Viewport is in OpenGL framebuffer; client buffer starts at (0,0).
.. _mjr_blitBuffer:
`mjr_blitBuffer <#mjr_blitBuffer>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjr_blitBuffer
Blit from src viewpoint in current framebuffer to dst viewport in other framebuffer.
If src, dst have different size and flg_depth==0, color is interpolated with GL_LINEAR.
.. _mjr_setAux:
`mjr_setAux <#mjr_setAux>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjr_setAux
Set Aux buffer for custom OpenGL rendering (call restoreBuffer when done).
.. _mjr_blitAux:
`mjr_blitAux <#mjr_blitAux>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjr_blitAux
Blit from Aux buffer to con->currentBuffer.
.. _mjr_text:
`mjr_text <#mjr_text>`__
~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjr_text
Draw text at (x,y) in relative coordinates; font is mjtFont.
.. _mjr_overlay:
`mjr_overlay <#mjr_overlay>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjr_overlay
Draw text overlay; font is mjtFont; gridpos is mjtGridPos.
.. _mjr_maxViewport:
`mjr_maxViewport <#mjr_maxViewport>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjr_maxViewport
Get maximum viewport for active buffer.
.. _mjr_rectangle:
`mjr_rectangle <#mjr_rectangle>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjr_rectangle
Draw rectangle.
.. _mjr_label:
`mjr_label <#mjr_label>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjr_label
Draw rectangle with centered text.
.. _mjr_figure:
`mjr_figure <#mjr_figure>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjr_figure
Draw 2D figure.
.. _mjr_render:
`mjr_render <#mjr_render>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjr_render
Render 3D scene.
.. _mjr_finish:
`mjr_finish <#mjr_finish>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjr_finish
Call glFinish.
.. _mjr_getError:
`mjr_getError <#mjr_getError>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjr_getError
Call glGetError and return result.
.. _mjr_findRect:
`mjr_findRect <#mjr_findRect>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjr_findRect
Find first rectangle containing mouse, -1: not found.
.. _UIframework:
UI framework
^^^^^^^^^^^^
For a high-level description of the UI framework, see :ref:`UI`.
.. _mjui_themeSpacing:
`mjui_themeSpacing <#mjui_themeSpacing>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjui_themeSpacing
Get builtin UI theme spacing (ind: 0-1).
.. _mjui_themeColor:
`mjui_themeColor <#mjui_themeColor>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjui_themeColor
Get builtin UI theme color (ind: 0-3).
.. _mjui_add:
`mjui_add <#mjui_add>`__
~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjui_add
This is the helper function used to construct a UI. The second argument points to an array of :ref:`mjuiDef` structs,
each corresponding to one item. The last (unused) item has its type set to -1, to mark termination. The items are added
after the end of the last used section. There is also another version of this function
(:ref:`mjui_addToSection<mjui_addToSection>`) which adds items to a specified section instead of adding them at the end
of the UI. Keep in mind that there is a maximum preallocated number of sections and items per section, given by
:ref:`mjMAXUISECT<glNumeric>` and :ref:`mjMAXUIITEM<glNumeric>`. Exceeding these maxima results in low-level errors.
.. _mjui_addToSection:
`mjui_addToSection <#mjui_addToSection>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjui_addToSection
Add definitions to UI section.
.. _mjui_resize:
`mjui_resize <#mjui_resize>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjui_resize
Compute UI sizes.
.. _mjui_update:
`mjui_update <#mjui_update>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjui_update
This is the main UI update function. It needs to be called whenever the user data (pointed to by the item data pointers)
changes, or when the UI state itself changes. It is normally called by a higher-level function implemented by the user
(``UiModify`` in :ref:`simulate.cc <saSimulate>`) which also recomputes the layout of all rectangles and associated
auxiliary buffers. The function updates the pixels in the offscreen OpenGL buffer. To perform minimal updates, the user
specifies the section and the item that was modified. A value of -1 means all items and/or sections need to be updated
(which is needed following major changes.)
.. _mjui_event:
`mjui_event <#mjui_event>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjui_event
This function is the low-level event handler. It makes the necessary changes in the UI and returns a pointer to the item
that received the event (or ``NULL`` if no valid event was recorded). This is normally called within the event handler
implemented by the user (``UiEvent`` in :ref:`simulate.cc <saSimulate>`), and then some action is taken by user code
depending on which UI item was modified and what the state of that item is after the event is handled.
.. _mjui_render:
`mjui_render <#mjui_render>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjui_render
This function is called in the screen refresh loop. It copies the offscreen OpenGL buffer to the window framebuffer. If
there are multiple UIs in the application, it should be called once for each UI. Thus ``mjui_render`` is called all the
time, while :ref:`mjui_update` is called only when changes in the UI take place. dsffsdg
.. _Derivatives-api:
Derivatives
^^^^^^^^^^^
The functions below provide useful derivatives of various functions, both analytic and
finite-differenced. The latter have names with the suffix ``FD``. Note that unlike much of the API,
outputs of derivative functions are the trailing rather than leading arguments.
.. _mjd_transitionFD:
`mjd_transitionFD <#mjd_transitionFD>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjd_transitionFD
Compute finite-differenced discrete-time transition matrices.
Letting :math:`x, u` denote the current :ref:`state<gePhysicsState>` and :ref:`control<geInput>`
vector in an mjData instance, and letting :math:`y, s` denote the next state and sensor
values, the top-level :ref:`mj_step` function computes :math:`(x,u) \rightarrow (y,s)`
:ref:`mjd_transitionFD` computes the four associated Jacobians using finite-differencing.
These matrices and their dimensions are:
.. csv-table::
:header: "matrix", "Jacobian", "dimension"
:widths: auto
:align: left
``A``, :math:`\partial y / \partial x`, ``2*nv+na x 2*nv+na``
``B``, :math:`\partial y / \partial u`, ``2*nv+na x nu``
``C``, :math:`\partial s / \partial x`, ``nsensordata x 2*nv+na``
``D``, :math:`\partial s / \partial u`, ``nsensordata x nu``
- All outputs are optional (can be NULL).
- ``eps`` is the finite-differencing epsilon.
- ``flg_centered`` denotes whether to use forward (0) or centered (1) differences.
- The Runge-Kutta integrator (:ref:`mjINT_RK4<mjtIntegrator>`) is not supported.
.. admonition:: Improving speed and accuracy
:class: tip
warmstart
If warm-starts are not :ref:`disabled<option-flag-warmstart>`, the warm-start accelerations
``mjData.qacc_warmstart`` which are present at call-time are loaded at the start of every relevant pipeline call,
to preserve determinism. If solver computations are an expensive part of the simulation, the following trick can
lead to significant speed-ups: First call :ref:`mj_forward` to let the solver converge, then reduce :ref:`solver
iterations<option-iterations>` significantly, then call :ref:`mjd_transitionFD`, finally, restore the original
value of :ref:`iterations<option-iterations>`. Because we are already near the solution, few iteration are required
to find the new minimum. This is especially true for the :ref:`Newton<option-solver>` solver, where the required
number of iteration for convergence near the minimum can be as low as 1.
tolerance
Accuracy can be improved if solver :ref:`tolerance<option-tolerance>` is set to 0. This means that all calls to
the solver will perform exactly the same number of iterations, preventing numerical errors due to early
termination. Of course, this means that :ref:`solver iterations<option-iterations>` should be small, to not tread
water at the minimum. This method and the one described above can and should be combined.
.. _mjd_inverseFD:
`mjd_inverseFD <#mjd_inverseFD>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjd_inverseFD
Finite differenced continuous-time inverse-dynamics Jacobians.
Letting :math:`x, a` denote the current :ref:`state<gePhysicsState>` and acceleration vectors in an mjData instance, and
letting :math:`f, s` denote the forces computed by the inverse dynamics (``qfrc_inverse``), the function
:ref:`mj_inverse` computes :math:`(x,a) \rightarrow (f,s)`. :ref:`mjd_inverseFD` computes seven associated Jacobians
using finite-differencing. These matrices and their dimensions are:
.. csv-table::
:header: "matrix", "Jacobian", "dimension"
:widths: auto
:align: left
``DfDq``, :math:`\partial f / \partial q`, ``nv x nv``
``DfDv``, :math:`\partial f / \partial v`, ``nv x nv``
``DfDa``, :math:`\partial f / \partial a`, ``nv x nv``
``DsDq``, :math:`\partial s / \partial q`, ``nv x nsensordata``
``DsDv``, :math:`\partial s / \partial v`, ``nv x nsensordata``
``DsDa``, :math:`\partial s / \partial a`, ``nv x nsensordata``
``DmDq``, :math:`\partial M / \partial q`, ``nv x nM``
- All outputs are optional (can be NULL).
- All outputs are transposed relative to Control Theory convention (i.e., column major).
- ``DmDq``, which contains a sparse representation of the ``nv x nv x nv`` tensor :math:`\partial M / \partial q`, is
not strictly an inverse dynamics Jacobian but is useful in related applications. It is provided as a convenience to
the user, since the required values are already computed if either of the other two :math:`\partial / \partial q`
Jacobians are requested.
- ``eps`` is the (forward) finite-differencing epsilon.
- ``flg_actuation`` denotes whether to subtract actuation forces (``qfrc_actuator``) from the output of the inverse
dynamics. If this flag is positive, actuator forces are not considered as external.
- The model option flag ``invdiscrete`` should correspond to the representation of ``mjData.qacc`` in order to compute
the correct derivative information.
.. attention::
- The Runge-Kutta 4th-order integrator (``mjINT_RK4``) is not supported.
- The noslip solver is not supported.
.. _mjd_subQuat:
`mjd_subQuat <#mjd_subQuat>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjd_subQuat
Derivatives of :ref:`mju_subQuat` (quaternion difference).
.. _mjd_quatIntegrate:
`mjd_quatIntegrate <#mjd_quatIntegrate>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjd_quatIntegrate
Derivatives of :ref:`mju_quatIntegrate`.
:math:`{\tt \small mju\_quatIntegrate}(q, v, h)` performs the in-place rotation :math:`q \leftarrow q + v h`,
where :math:`q \in \mathbf{S}^3` is a unit quaternion, :math:`v \in \mathbf{R}^3` is a 3D angular velocity and
:math:`h \in \mathbf{R^+}` is a timestep. This is equivalent to :math:`{\tt \small mju\_quatIntegrate}(q, s, 1.0)`,
where :math:`s` is the scaled velocity :math:`s = h v`.
:math:`{\tt \small mjd\_quatIntegrate}(v, h, D_q, D_v, D_h)` computes the Jacobians of the output :math:`q` with respect
to the inputs. Below, :math:`\bar q` denotes the pre-modified quaternion:
.. math::
\begin{aligned}
D_q &= \partial q / \partial \bar q \\
D_v &= \partial q / \partial v \\
D_h &= \partial q / \partial h
\end{aligned}
Note that derivatives depend only on :math:`h` and :math:`v` (in fact, on :math:`s = h v`).
All outputs are optional.
.. _Plugins-api:
Plugins
^^^^^^^
.. _mjp_defaultPlugin:
`mjp_defaultPlugin <#mjp_defaultPlugin>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjp_defaultPlugin
Set default plugin definition.
.. _mjp_registerPlugin:
`mjp_registerPlugin <#mjp_registerPlugin>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjp_registerPlugin
Globally register a plugin. This function is thread-safe.
If an identical mjpPlugin is already registered, this function does nothing.
If a non-identical mjpPlugin with the same name is already registered, an mju_error is raised.
Two mjpPlugins are considered identical if all member function pointers and numbers are equal,
and the name and attribute strings are all identical, however the char pointers to the strings
need not be the same.
.. _mjp_pluginCount:
`mjp_pluginCount <#mjp_pluginCount>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjp_pluginCount
Return the number of globally registered plugins.
.. _mjp_getPlugin:
`mjp_getPlugin <#mjp_getPlugin>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjp_getPlugin
Look up a plugin by name. If slot is not NULL, also write its registered slot number into it.
.. _mjp_getPluginAtSlot:
`mjp_getPluginAtSlot <#mjp_getPluginAtSlot>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjp_getPluginAtSlot
Look up a plugin by the registered slot number that was returned by mjp_registerPlugin.
.. _mjp_defaultResourceProvider:
`mjp_defaultResourceProvider <#mjp_defaultResourceProvider>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjp_defaultResourceProvider
Set default resource provider definition.
.. _mjp_registerResourceProvider:
`mjp_registerResourceProvider <#mjp_registerResourceProvider>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjp_registerResourceProvider
Globally register a resource provider in a thread-safe manner. The provider must have a prefix
that is not a sub-prefix or super-prefix of any current registered providers. This function
returns a slot number > 0 on success.
.. _mjp_resourceProviderCount:
`mjp_resourceProviderCount <#mjp_resourceProviderCount>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjp_resourceProviderCount
Return the number of globally registered resource providers.
.. _mjp_getResourceProvider:
`mjp_getResourceProvider <#mjp_getResourceProvider>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjp_getResourceProvider
Return the resource provider with the prefix that matches against the resource name.
If no match, return NULL.
.. _mjp_getResourceProviderAtSlot:
`mjp_getResourceProviderAtSlot <#mjp_getResourceProviderAtSlot>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjp_getResourceProviderAtSlot
Look up a resource provider by slot number returned by mjp_registerResourceProvider.
If invalid slot number, return NULL.
.. _Thread:
Threads
^^^^^^^
.. _mju_threadPoolCreate:
`mju_threadPoolCreate <#mju_threadPoolCreate>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_threadPoolCreate
Create a thread pool with the specified number of threads running.
.. _mju_bindThreadPool:
`mju_bindThreadPool <#mju_bindThreadPool>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_bindThreadPool
Adds a thread pool to mjData and configures it for multi-threaded use.
.. _mju_threadPoolEnqueue:
`mju_threadPoolEnqueue <#mju_threadPoolEnqueue>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_threadPoolEnqueue
Enqueue a task in a thread pool.
.. _mju_threadPoolDestroy:
`mju_threadPoolDestroy <#mju_threadPoolDestroy>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_threadPoolDestroy
Destroy a thread pool.
.. _mju_defaultTask:
`mju_defaultTask <#mju_defaultTask>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_defaultTask
Initialize an mjTask.
.. _mju_taskJoin:
`mju_taskJoin <#mju_taskJoin>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_taskJoin
Wait for a task to complete.
.. _Standardmath:
Standard math
^^^^^^^^^^^^^
The "functions" in this section are preprocessor macros replaced with the corresponding C standard library math
functions. When MuJoCo is compiled with single precision (which is not currently available to the public, but we
sometimes use it internally) these macros are replaced with the corresponding single-precision functions (not shown
here). So one can think of them as having inputs and outputs of type mjtNum, where mjtNum is defined as double or float
depending on how MuJoCo is compiled. We will not document these functions here; see the C standard library
specification.
mju_sqrt
~~~~~~~~
.. code-block:: C
#define mju_sqrt sqrt
mju_exp
~~~~~~~
.. code-block:: C
#define mju_exp exp
mju_sin
~~~~~~~
.. code-block:: C
#define mju_sin sin
mju_cos
~~~~~~~
.. code-block:: C
#define mju_cos cos
mju_tan
~~~~~~~
.. code-block:: C
#define mju_tan tan
mju_asin
~~~~~~~~
.. code-block:: C
#define mju_asin asin
mju_acos
~~~~~~~~
.. code-block:: C
#define mju_acos acos
mju_atan2
~~~~~~~~~
.. code-block:: C
#define mju_atan2 atan2
mju_tanh
~~~~~~~~
.. code-block:: C
#define mju_tanh tanh
mju_pow
~~~~~~~
.. code-block:: C
#define mju_pow pow
mju_abs
~~~~~~~
.. code-block:: C
#define mju_abs fabs
mju_log
~~~~~~~
.. code-block:: C
#define mju_log log
mju_log10
~~~~~~~~~
.. code-block:: C
#define mju_log10 log10
mju_floor
~~~~~~~~~
.. code-block:: C
#define mju_floor floor
mju_ceil
~~~~~~~~
.. code-block:: C
#define mju_ceil ceil
.. _Vectormath:
Vector math
^^^^^^^^^^^
.. _mju_zero3:
`mju_zero3 <#mju_zero3>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_zero3
Set res = 0.
.. _mju_copy3:
`mju_copy3 <#mju_copy3>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_copy3
Set res = vec.
.. _mju_scl3:
`mju_scl3 <#mju_scl3>`__
~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_scl3
Set res = vec*scl.
.. _mju_add3:
`mju_add3 <#mju_add3>`__
~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_add3
Set res = vec1 + vec2.
.. _mju_sub3:
`mju_sub3 <#mju_sub3>`__
~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_sub3
Set res = vec1 - vec2.
.. _mju_addTo3:
`mju_addTo3 <#mju_addTo3>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_addTo3
Set res = res + vec.
.. _mju_subFrom3:
`mju_subFrom3 <#mju_subFrom3>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_subFrom3
Set res = res - vec.
.. _mju_addToScl3:
`mju_addToScl3 <#mju_addToScl3>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_addToScl3
Set res = res + vec*scl.
.. _mju_addScl3:
`mju_addScl3 <#mju_addScl3>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_addScl3
Set res = vec1 + vec2*scl.
.. _mju_normalize3:
`mju_normalize3 <#mju_normalize3>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_normalize3
Normalize vector, return length before normalization.
.. _mju_norm3:
`mju_norm3 <#mju_norm3>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_norm3
Return vector length (without normalizing the vector).
.. _mju_dot3:
`mju_dot3 <#mju_dot3>`__
~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_dot3
Return dot-product of vec1 and vec2.
.. _mju_dist3:
`mju_dist3 <#mju_dist3>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_dist3
Return Cartesian distance between 3D vectors pos1 and pos2.
.. _mju_mulMatVec3:
`mju_mulMatVec3 <#mju_mulMatVec3>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_mulMatVec3
Multiply 3-by-3 matrix by vector: res = mat * vec.
.. _mju_mulMatTVec3:
`mju_mulMatTVec3 <#mju_mulMatTVec3>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_mulMatTVec3
Multiply transposed 3-by-3 matrix by vector: res = mat' * vec.
.. _mju_cross:
`mju_cross <#mju_cross>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_cross
Compute cross-product: res = cross(a, b).
.. _mju_zero4:
`mju_zero4 <#mju_zero4>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_zero4
Set res = 0.
.. _mju_unit4:
`mju_unit4 <#mju_unit4>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_unit4
Set res = (1,0,0,0).
.. _mju_copy4:
`mju_copy4 <#mju_copy4>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_copy4
Set res = vec.
.. _mju_normalize4:
`mju_normalize4 <#mju_normalize4>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_normalize4
Normalize vector, return length before normalization.
.. _mju_zero:
`mju_zero <#mju_zero>`__
~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_zero
Set res = 0.
.. _mju_fill:
`mju_fill <#mju_fill>`__
~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_fill
Set res = val.
.. _mju_copy:
`mju_copy <#mju_copy>`__
~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_copy
Set res = vec.
.. _mju_sum:
`mju_sum <#mju_sum>`__
~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_sum
Return sum(vec).
.. _mju_L1:
`mju_L1 <#mju_L1>`__
~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_L1
Return L1 norm: sum(abs(vec)).
.. _mju_scl:
`mju_scl <#mju_scl>`__
~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_scl
Set res = vec*scl.
.. _mju_add:
`mju_add <#mju_add>`__
~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_add
Set res = vec1 + vec2.
.. _mju_sub:
`mju_sub <#mju_sub>`__
~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_sub
Set res = vec1 - vec2.
.. _mju_addTo:
`mju_addTo <#mju_addTo>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_addTo
Set res = res + vec.
.. _mju_subFrom:
`mju_subFrom <#mju_subFrom>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_subFrom
Set res = res - vec.
.. _mju_addToScl:
`mju_addToScl <#mju_addToScl>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_addToScl
Set res = res + vec*scl.
.. _mju_addScl:
`mju_addScl <#mju_addScl>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_addScl
Set res = vec1 + vec2*scl.
.. _mju_normalize:
`mju_normalize <#mju_normalize>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_normalize
Normalize vector, return length before normalization.
.. _mju_norm:
`mju_norm <#mju_norm>`__
~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_norm
Return vector length (without normalizing vector).
.. _mju_dot:
`mju_dot <#mju_dot>`__
~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_dot
Return dot-product of vec1 and vec2.
.. _mju_mulMatVec:
`mju_mulMatVec <#mju_mulMatVec>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_mulMatVec
Multiply matrix and vector: res = mat * vec.
.. _mju_mulMatTVec:
`mju_mulMatTVec <#mju_mulMatTVec>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_mulMatTVec
Multiply transposed matrix and vector: res = mat' * vec.
.. _mju_mulVecMatVec:
`mju_mulVecMatVec <#mju_mulVecMatVec>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_mulVecMatVec
Multiply square matrix with vectors on both sides: returns vec1' * mat * vec2.
.. _mju_transpose:
`mju_transpose <#mju_transpose>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_transpose
Transpose matrix: res = mat'.
.. _mju_symmetrize:
`mju_symmetrize <#mju_symmetrize>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_symmetrize
Symmetrize square matrix :math:`R = \frac{1}{2}(M + M^T)`.
.. _mju_eye:
`mju_eye <#mju_eye>`__
~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_eye
Set mat to the identity matrix.
.. _mju_mulMatMat:
`mju_mulMatMat <#mju_mulMatMat>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_mulMatMat
Multiply matrices: res = mat1 * mat2.
.. _mju_mulMatMatT:
`mju_mulMatMatT <#mju_mulMatMatT>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_mulMatMatT
Multiply matrices, second argument transposed: res = mat1 * mat2'.
.. _mju_mulMatTMat:
`mju_mulMatTMat <#mju_mulMatTMat>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_mulMatTMat
Multiply matrices, first argument transposed: res = mat1' * mat2.
.. _mju_sqrMatTD:
`mju_sqrMatTD <#mju_sqrMatTD>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_sqrMatTD
Set res = mat' * diag * mat if diag is not NULL, and res = mat' * mat otherwise.
.. _mju_transformSpatial:
`mju_transformSpatial <#mju_transformSpatial>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_transformSpatial
Coordinate transform of 6D motion or force vector in rotation:translation format.
rotnew2old is 3-by-3, NULL means no rotation; flg_force specifies force or motion type.
.. _Sparsemath:
Sparse math
^^^^^^^^^^^
.. _mju_dense2sparse:
`mju_dense2sparse <#mju_dense2sparse>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_dense2sparse
Convert matrix from dense to sparse.
nnz is size of res and colind, return 1 if too small, 0 otherwise.
.. _mju_sparse2dense:
`mju_sparse2dense <#mju_sparse2dense>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_sparse2dense
Convert matrix from sparse to dense.
.. _Quaternions:
Quaternions
^^^^^^^^^^^
.. _mju_rotVecQuat:
`mju_rotVecQuat <#mju_rotVecQuat>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_rotVecQuat
Rotate vector by quaternion.
.. _mju_negQuat:
`mju_negQuat <#mju_negQuat>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_negQuat
Conjugate quaternion, corresponding to opposite rotation.
.. _mju_mulQuat:
`mju_mulQuat <#mju_mulQuat>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_mulQuat
Multiply quaternions.
.. _mju_mulQuatAxis:
`mju_mulQuatAxis <#mju_mulQuatAxis>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_mulQuatAxis
Multiply quaternion and axis.
.. _mju_axisAngle2Quat:
`mju_axisAngle2Quat <#mju_axisAngle2Quat>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_axisAngle2Quat
Convert axisAngle to quaternion.
.. _mju_quat2Vel:
`mju_quat2Vel <#mju_quat2Vel>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_quat2Vel
Convert quaternion (corresponding to orientation difference) to 3D velocity.
.. _mju_subQuat:
`mju_subQuat <#mju_subQuat>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_subQuat
Subtract quaternions, express as 3D velocity: qb*quat(res) = qa.
.. _mju_quat2Mat:
`mju_quat2Mat <#mju_quat2Mat>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_quat2Mat
Convert quaternion to 3D rotation matrix.
.. _mju_mat2Quat:
`mju_mat2Quat <#mju_mat2Quat>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_mat2Quat
Convert 3D rotation matrix to quaternion.
.. _mju_derivQuat:
`mju_derivQuat <#mju_derivQuat>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_derivQuat
Compute time-derivative of quaternion, given 3D rotational velocity.
.. _mju_quatIntegrate:
`mju_quatIntegrate <#mju_quatIntegrate>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_quatIntegrate
Integrate quaternion given 3D angular velocity.
.. _mju_quatZ2Vec:
`mju_quatZ2Vec <#mju_quatZ2Vec>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_quatZ2Vec
Construct quaternion performing rotation from z-axis to given vector.
.. _mju_mat2Rot:
`mju_mat2Rot <#mju_mat2Rot>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_mat2Rot
Extract 3D rotation from an arbitrary 3x3 matrix by refining the input quaternion.
Returns the number of iterations required to converge
.. _mju_euler2Quat:
`mju_euler2Quat <#mju_euler2Quat>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_euler2Quat
Convert sequence of Euler angles (radians) to quaternion.
seq[0,1,2] must be in 'xyzXYZ', lower/upper-case mean intrinsic/extrinsic rotations.
.. _Poses:
Poses
^^^^^
.. _mju_mulPose:
`mju_mulPose <#mju_mulPose>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_mulPose
Multiply two poses.
.. _mju_negPose:
`mju_negPose <#mju_negPose>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_negPose
Conjugate pose, corresponding to the opposite spatial transformation.
.. _mju_trnVecPose:
`mju_trnVecPose <#mju_trnVecPose>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_trnVecPose
Transform vector by pose.
.. _Decompositions:
Decompositions / Solvers
^^^^^^^^^^^^^^^^^^^^^^^^
.. _mju_cholFactor:
`mju_cholFactor <#mju_cholFactor>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_cholFactor
Cholesky decomposition: mat = L*L'; return rank, decomposition performed in-place into mat.
.. _mju_cholSolve:
`mju_cholSolve <#mju_cholSolve>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_cholSolve
Solve (mat*mat') * res = vec, where mat is a Cholesky factor.
.. _mju_cholUpdate:
`mju_cholUpdate <#mju_cholUpdate>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_cholUpdate
Cholesky rank-one update: L*L' +/- x*x'; return rank.
.. _mju_cholFactorBand:
`mju_cholFactorBand <#mju_cholFactorBand>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_cholFactorBand
Band-dense Cholesky decomposition.
|br| Add ``diagadd + diagmul*mat_ii`` to diagonal before decomposition.
|br| Returns the minimum value of the factorized diagonal or 0 if rank-deficient.
**Symmetric band-dense matrices**
:ref:`mju_cholFactorBand` and subsequent functions containing the substring "band" operate on matrices which are a
generalization of symmetric `band matrices <https://en.wikipedia.org/wiki/Band_matrix>`_. *Symmetric band-dense* or
"arrowhead" matrices have non-zeros along proximal diagonal bands and dense blocks on the bottom rows and right
columns. These matrices have the property that Cholesky factorization creates no fill-in and can therefore be
performed efficiently in-place. Matrix structure is defined by three integers:
- ``ntotal``: the number of rows (columns) of the symmetric matrix.
- ``nband``: the number of bands under (over) the diagonal, inclusive of the diagonal.
- ``ndense``: the number of dense rows (columns) at the bottom (right).
The non-zeros are stored in memory as two contiguous row-major blocks, colored green and blue in the illustration
below. The first block has size ``nband x (ntotal-ndense)`` and contains the diagonal and the bands below it. The
second block has size ``ndense x ntotal`` and contains the dense part. Total required memory is the sum of the block
sizes.
.. figure:: /images/APIreference/arrowhead.svg
:width: 750px
:align: left
For example, consider an arrowhead matrix with ``nband = 3``, ``ndense = 2`` and ``ntotal = 8``. In this example, the
total memory required is ``3*(8-2) + 2*8 = 34`` mjtNum's, laid out as follows:
.. code-block::
0 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
The diagonal elements are ``2, 5, 8, 11, 14, 17, 24, 33``.
|br| Elements ``0, 1, 3, 25`` are present in memory but never touched.
.. _mju_cholSolveBand:
`mju_cholSolveBand <#mju_cholSolveBand>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_cholSolveBand
Solve (mat*mat')*res = vec where mat is a band-dense Cholesky factor.
.. _mju_band2Dense:
`mju_band2Dense <#mju_band2Dense>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_band2Dense
Convert banded matrix to dense matrix, fill upper triangle if flg_sym>0.
.. _mju_dense2Band:
`mju_dense2Band <#mju_dense2Band>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_dense2Band
Convert dense matrix to banded matrix.
.. _mju_bandMulMatVec:
`mju_bandMulMatVec <#mju_bandMulMatVec>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_bandMulMatVec
Multiply band-diagonal matrix with nvec vectors, include upper triangle if flg_sym>0.
.. _mju_bandDiag:
`mju_bandDiag <#mju_bandDiag>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_bandDiag
Address of diagonal element i in band-dense matrix representation.
.. _mju_eig3:
`mju_eig3 <#mju_eig3>`__
~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_eig3
Eigenvalue decomposition of symmetric 3x3 matrix, mat = eigvec * diag(eigval) * eigvec'.
.. _mju_boxQP:
`mju_boxQP <#mju_boxQP>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_boxQP
Minimize :math:`\tfrac{1}{2} x^T H x + x^T g \quad \text{s.t.} \quad l \le x \le u`, return rank or -1 if failed.
inputs:
``n`` - problem dimension
``H`` - SPD matrix ``n*n``
``g`` - bias vector ``n``
``lower`` - lower bounds ``n``
``upper`` - upper bounds ``n``
``res`` - solution warmstart ``n``
return value:
``nfree <= n`` - rank of unconstrained subspace, -1 if failure
outputs (required):
``res`` - solution ``n``
``R`` - subspace Cholesky factor ``nfree*nfree``, allocated: ``n*(n+7)``
outputs (optional):
``index`` - set of free dimensions ``nfree``, allocated: ``n``
notes:
The initial value of ``res`` is used to warmstart the solver.
``R`` must have allocated size ``n*(n+7)``, but only ``nfree*nfree`` values are used as output.
``index`` (if given) must have allocated size ``n``, but only ``nfree`` values are used as output.
The convenience function :ref:`mju_boxQPmalloc` allocates the required data structures.
Only the lower triangles of H and R are read from and written to, respectively.
.. _mju_boxQPmalloc:
`mju_boxQPmalloc <#mju_boxQPmalloc>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mju_boxQPmalloc
Allocate heap memory for box-constrained Quadratic Program.
As in :ref:`mju_boxQP`, ``index``, ``lower``, and ``upper`` are optional.
Free all pointers with ``mju_free()``.
.. _Attachment:
Attachment
^^^^^^^^^^
.. _mjs_attach:
`mjs_attach <#mjs_attach>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_attach
Attach child to a parent, return the attached element if success or NULL otherwise.
.. _AddTreeElements:
Tree elements
^^^^^^^^^^^^^
.. _mjs_addBody:
`mjs_addBody <#mjs_addBody>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_addBody
Add child body to body, return child.
.. _mjs_addSite:
`mjs_addSite <#mjs_addSite>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_addSite
Add site to body, return site spec.
.. _mjs_addJoint:
`mjs_addJoint <#mjs_addJoint>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_addJoint
Add joint to body.
.. _mjs_addFreeJoint:
`mjs_addFreeJoint <#mjs_addFreeJoint>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_addFreeJoint
Add freejoint to body.
.. _mjs_addGeom:
`mjs_addGeom <#mjs_addGeom>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_addGeom
Add geom to body.
.. _mjs_addCamera:
`mjs_addCamera <#mjs_addCamera>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_addCamera
Add camera to body.
.. _mjs_addLight:
`mjs_addLight <#mjs_addLight>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_addLight
Add light to body.
.. _mjs_addFrame:
`mjs_addFrame <#mjs_addFrame>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_addFrame
Add frame to body.
.. _mjs_delete:
`mjs_delete <#mjs_delete>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_delete
Remove object corresponding to the given element, return 0 on success.
.. _AddNonTreeElements:
Non-tree elements
^^^^^^^^^^^^^^^^^
.. _mjs_addActuator:
`mjs_addActuator <#mjs_addActuator>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_addActuator
Add actuator.
.. _mjs_addSensor:
`mjs_addSensor <#mjs_addSensor>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_addSensor
Add sensor.
.. _mjs_addFlex:
`mjs_addFlex <#mjs_addFlex>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_addFlex
Add flex.
.. _mjs_addPair:
`mjs_addPair <#mjs_addPair>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_addPair
Add contact pair.
.. _mjs_addExclude:
`mjs_addExclude <#mjs_addExclude>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_addExclude
Add excluded body pair.
.. _mjs_addEquality:
`mjs_addEquality <#mjs_addEquality>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_addEquality
Add equality.
.. _mjs_addTendon:
`mjs_addTendon <#mjs_addTendon>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_addTendon
Add tendon.
.. _mjs_wrapSite:
`mjs_wrapSite <#mjs_wrapSite>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_wrapSite
Wrap site using tendon.
.. _mjs_wrapGeom:
`mjs_wrapGeom <#mjs_wrapGeom>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_wrapGeom
Wrap geom using tendon.
.. _mjs_wrapJoint:
`mjs_wrapJoint <#mjs_wrapJoint>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_wrapJoint
Wrap joint using tendon.
.. _mjs_wrapPulley:
`mjs_wrapPulley <#mjs_wrapPulley>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_wrapPulley
Wrap pulley using tendon.
.. _mjs_addNumeric:
`mjs_addNumeric <#mjs_addNumeric>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_addNumeric
Add numeric.
.. _mjs_addText:
`mjs_addText <#mjs_addText>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_addText
Add text.
.. _mjs_addTuple:
`mjs_addTuple <#mjs_addTuple>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_addTuple
Add tuple.
.. _mjs_addKey:
`mjs_addKey <#mjs_addKey>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_addKey
Add keyframe.
.. _mjs_addPlugin:
`mjs_addPlugin <#mjs_addPlugin>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_addPlugin
Add plugin.
.. _mjs_addDefault:
`mjs_addDefault <#mjs_addDefault>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_addDefault
Add default.
.. _AddAssets:
Assets
^^^^^^
.. _mjs_addMesh:
`mjs_addMesh <#mjs_addMesh>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_addMesh
Add mesh.
.. _mjs_addHField:
`mjs_addHField <#mjs_addHField>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_addHField
Add height field.
.. _mjs_addSkin:
`mjs_addSkin <#mjs_addSkin>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_addSkin
Add skin.
.. _mjs_addTexture:
`mjs_addTexture <#mjs_addTexture>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_addTexture
Add texture.
.. _mjs_addMaterial:
`mjs_addMaterial <#mjs_addMaterial>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_addMaterial
Add material.
.. _FindAndGetUtilities:
Find and get utilities
^^^^^^^^^^^^^^^^^^^^^^
.. _mjs_getSpec:
`mjs_getSpec <#mjs_getSpec>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_getSpec
Get spec from body.
.. _mjs_findSpec:
`mjs_findSpec <#mjs_findSpec>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_findSpec
Find spec (model asset) by name.
.. _mjs_findBody:
`mjs_findBody <#mjs_findBody>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_findBody
Find body in spec by name.
.. _mjs_findElement:
`mjs_findElement <#mjs_findElement>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_findElement
Find element in spec by name.
.. _mjs_findChild:
`mjs_findChild <#mjs_findChild>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_findChild
Find child body by name.
.. _mjs_getParent:
`mjs_getParent <#mjs_getParent>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_getParent
Get parent body.
.. _mjs_getFrame:
`mjs_getFrame <#mjs_getFrame>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_getFrame
Get parent frame.
.. _mjs_findFrame:
`mjs_findFrame <#mjs_findFrame>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_findFrame
Find frame by name.
.. _mjs_getDefault:
`mjs_getDefault <#mjs_getDefault>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_getDefault
Get default corresponding to an element.
.. _mjs_findDefault:
`mjs_findDefault <#mjs_findDefault>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_findDefault
Find default in model by class name.
.. _mjs_getSpecDefault:
`mjs_getSpecDefault <#mjs_getSpecDefault>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_getSpecDefault
Get global default from model.
.. _mjs_getId:
`mjs_getId <#mjs_getId>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_getId
Get element id.
.. _mjs_firstChild:
`mjs_firstChild <#mjs_firstChild>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_firstChild
Return body's first child of given type. If recurse is nonzero, also search the body's subtree.
.. _mjs_nextChild:
`mjs_nextChild <#mjs_nextChild>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_nextChild
Return body's next child of the same type; return NULL if child is last.
If recurse is nonzero, also search the body's subtree.
.. _mjs_firstElement:
`mjs_firstElement <#mjs_firstElement>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_firstElement
Return spec's first element of selected type.
.. _mjs_nextElement:
`mjs_nextElement <#mjs_nextElement>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_nextElement
Return spec's next element; return NULL if element is last.
.. _AttributeSetters:
Attribute setters
^^^^^^^^^^^^^^^^^
.. _mjs_setName:
`mjs_setName <#mjs_setName>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_setName
Set element's name, return 0 on success.
.. _mjs_setBuffer:
`mjs_setBuffer <#mjs_setBuffer>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_setBuffer
Copy buffer.
.. _mjs_setString:
`mjs_setString <#mjs_setString>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_setString
Copy text to string.
.. _mjs_setStringVec:
`mjs_setStringVec <#mjs_setStringVec>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_setStringVec
Split text to entries and copy to string vector.
.. _mjs_setInStringVec:
`mjs_setInStringVec <#mjs_setInStringVec>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_setInStringVec
Set entry in string vector.
.. _mjs_appendString:
`mjs_appendString <#mjs_appendString>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_appendString
Append text entry to string vector.
.. _mjs_setInt:
`mjs_setInt <#mjs_setInt>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_setInt
Copy int array to vector.
.. _mjs_appendIntVec:
`mjs_appendIntVec <#mjs_appendIntVec>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_appendIntVec
Append int array to vector of arrays.
.. _mjs_setFloat:
`mjs_setFloat <#mjs_setFloat>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_setFloat
Copy float array to vector.
.. _mjs_appendFloatVec:
`mjs_appendFloatVec <#mjs_appendFloatVec>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_appendFloatVec
Append float array to vector of arrays.
.. _mjs_setDouble:
`mjs_setDouble <#mjs_setDouble>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_setDouble
Copy double array to vector.
.. _mjs_setPluginAttributes:
`mjs_setPluginAttributes <#mjs_setPluginAttributes>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_setPluginAttributes
Set plugin attributes.
.. _AttributeGetters:
Attribute getters
^^^^^^^^^^^^^^^^^
.. _mjs_getName:
`mjs_getName <#mjs_getName>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_getName
Get element's name.
.. _mjs_getString:
`mjs_getString <#mjs_getString>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_getString
Get string contents.
.. _mjs_getDouble:
`mjs_getDouble <#mjs_getDouble>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_getDouble
Get double array contents and optionally its size.
.. _mjs_getPluginAttributes:
`mjs_getPluginAttributes <#mjs_getPluginAttributes>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_getPluginAttributes
Get plugin attributes.
.. _SpecUtilities:
Spec utilities
^^^^^^^^^^^^^^
.. _mjs_setDefault:
`mjs_setDefault <#mjs_setDefault>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_setDefault
Set element's default.
.. _mjs_setFrame:
`mjs_setFrame <#mjs_setFrame>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_setFrame
Set element's enclosing frame, return 0 on success.
.. _mjs_resolveOrientation:
`mjs_resolveOrientation <#mjs_resolveOrientation>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_resolveOrientation
Resolve alternative orientations to quat, return error if any.
.. _mjs_bodyToFrame:
`mjs_bodyToFrame <#mjs_bodyToFrame>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_bodyToFrame
Transform body into a frame.
.. _mjs_setUserValue:
`mjs_setUserValue <#mjs_setUserValue>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_setUserValue
Set user payload, overriding the existing value for the specified key if present.
.. _mjs_setUserValueWithCleanup:
`mjs_setUserValueWithCleanup <#mjs_setUserValueWithCleanup>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_setUserValueWithCleanup
Set user payload, overriding the existing value for the specified key if
present. This version differs from mjs_setUserValue in that it takes a
cleanup function that will be called when the user payload is deleted.
.. _mjs_getUserValue:
`mjs_getUserValue <#mjs_getUserValue>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_getUserValue
Return user payload or NULL if none found.
.. _mjs_deleteUserValue:
`mjs_deleteUserValue <#mjs_deleteUserValue>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_deleteUserValue
Delete user payload.
.. _ElementInitialization:
Element initialization
^^^^^^^^^^^^^^^^^^^^^^
.. _mjs_defaultSpec:
`mjs_defaultSpec <#mjs_defaultSpec>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_defaultSpec
Default spec attributes.
.. _mjs_defaultOrientation:
`mjs_defaultOrientation <#mjs_defaultOrientation>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_defaultOrientation
Default orientation attributes.
.. _mjs_defaultBody:
`mjs_defaultBody <#mjs_defaultBody>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_defaultBody
Default body attributes.
.. _mjs_defaultFrame:
`mjs_defaultFrame <#mjs_defaultFrame>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_defaultFrame
Default frame attributes.
.. _mjs_defaultJoint:
`mjs_defaultJoint <#mjs_defaultJoint>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_defaultJoint
Default joint attributes.
.. _mjs_defaultGeom:
`mjs_defaultGeom <#mjs_defaultGeom>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_defaultGeom
Default geom attributes.
.. _mjs_defaultSite:
`mjs_defaultSite <#mjs_defaultSite>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_defaultSite
Default site attributes.
.. _mjs_defaultCamera:
`mjs_defaultCamera <#mjs_defaultCamera>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_defaultCamera
Default camera attributes.
.. _mjs_defaultLight:
`mjs_defaultLight <#mjs_defaultLight>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_defaultLight
Default light attributes.
.. _mjs_defaultFlex:
`mjs_defaultFlex <#mjs_defaultFlex>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_defaultFlex
Default flex attributes.
.. _mjs_defaultMesh:
`mjs_defaultMesh <#mjs_defaultMesh>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_defaultMesh
Default mesh attributes.
.. _mjs_defaultHField:
`mjs_defaultHField <#mjs_defaultHField>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_defaultHField
Default height field attributes.
.. _mjs_defaultSkin:
`mjs_defaultSkin <#mjs_defaultSkin>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_defaultSkin
Default skin attributes.
.. _mjs_defaultTexture:
`mjs_defaultTexture <#mjs_defaultTexture>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_defaultTexture
Default texture attributes.
.. _mjs_defaultMaterial:
`mjs_defaultMaterial <#mjs_defaultMaterial>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_defaultMaterial
Default material attributes.
.. _mjs_defaultPair:
`mjs_defaultPair <#mjs_defaultPair>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_defaultPair
Default pair attributes.
.. _mjs_defaultEquality:
`mjs_defaultEquality <#mjs_defaultEquality>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_defaultEquality
Default equality attributes.
.. _mjs_defaultTendon:
`mjs_defaultTendon <#mjs_defaultTendon>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_defaultTendon
Default tendon attributes.
.. _mjs_defaultActuator:
`mjs_defaultActuator <#mjs_defaultActuator>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_defaultActuator
Default actuator attributes.
.. _mjs_defaultSensor:
`mjs_defaultSensor <#mjs_defaultSensor>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_defaultSensor
Default sensor attributes.
.. _mjs_defaultNumeric:
`mjs_defaultNumeric <#mjs_defaultNumeric>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_defaultNumeric
Default numeric attributes.
.. _mjs_defaultText:
`mjs_defaultText <#mjs_defaultText>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_defaultText
Default text attributes.
.. _mjs_defaultTuple:
`mjs_defaultTuple <#mjs_defaultTuple>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_defaultTuple
Default tuple attributes.
.. _mjs_defaultKey:
`mjs_defaultKey <#mjs_defaultKey>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_defaultKey
Default keyframe attributes.
.. _mjs_defaultPlugin:
`mjs_defaultPlugin <#mjs_defaultPlugin>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_defaultPlugin
Default plugin attributes.
.. _ElementCasting:
Element casting
^^^^^^^^^^^^^^^
.. _mjs_asBody:
`mjs_asBody <#mjs_asBody>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_asBody
Safely cast an element as mjsBody, or return NULL if the element is not an mjsBody.
.. _mjs_asGeom:
`mjs_asGeom <#mjs_asGeom>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_asGeom
Safely cast an element as mjsGeom, or return NULL if the element is not an mjsGeom.
.. _mjs_asJoint:
`mjs_asJoint <#mjs_asJoint>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_asJoint
Safely cast an element as mjsJoint, or return NULL if the element is not an mjsJoint.
.. _mjs_asSite:
`mjs_asSite <#mjs_asSite>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_asSite
Safely cast an element as mjsSite, or return NULL if the element is not an mjsSite.
.. _mjs_asCamera:
`mjs_asCamera <#mjs_asCamera>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_asCamera
Safely cast an element as mjsCamera, or return NULL if the element is not an mjsCamera.
.. _mjs_asLight:
`mjs_asLight <#mjs_asLight>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_asLight
Safely cast an element as mjsLight, or return NULL if the element is not an mjsLight.
.. _mjs_asFrame:
`mjs_asFrame <#mjs_asFrame>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_asFrame
Safely cast an element as mjsFrame, or return NULL if the element is not an mjsFrame.
.. _mjs_asActuator:
`mjs_asActuator <#mjs_asActuator>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_asActuator
Safely cast an element as mjsActuator, or return NULL if the element is not an mjsActuator.
.. _mjs_asSensor:
`mjs_asSensor <#mjs_asSensor>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_asSensor
Safely cast an element as mjsSensor, or return NULL if the element is not an mjsSensor.
.. _mjs_asFlex:
`mjs_asFlex <#mjs_asFlex>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_asFlex
Safely cast an element as mjsFlex, or return NULL if the element is not an mjsFlex.
.. _mjs_asPair:
`mjs_asPair <#mjs_asPair>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_asPair
Safely cast an element as mjsPair, or return NULL if the element is not an mjsPair.
.. _mjs_asEquality:
`mjs_asEquality <#mjs_asEquality>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_asEquality
Safely cast an element as mjsEquality, or return NULL if the element is not an mjsEquality.
.. _mjs_asExclude:
`mjs_asExclude <#mjs_asExclude>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_asExclude
Safely cast an element as mjsExclude, or return NULL if the element is not an mjsExclude.
.. _mjs_asTendon:
`mjs_asTendon <#mjs_asTendon>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_asTendon
Safely cast an element as mjsTendon, or return NULL if the element is not an mjsTendon.
.. _mjs_asNumeric:
`mjs_asNumeric <#mjs_asNumeric>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_asNumeric
Safely cast an element as mjsNumeric, or return NULL if the element is not an mjsNumeric.
.. _mjs_asText:
`mjs_asText <#mjs_asText>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_asText
Safely cast an element as mjsText, or return NULL if the element is not an mjsText.
.. _mjs_asTuple:
`mjs_asTuple <#mjs_asTuple>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_asTuple
Safely cast an element as mjsTuple, or return NULL if the element is not an mjsTuple.
.. _mjs_asKey:
`mjs_asKey <#mjs_asKey>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_asKey
Safely cast an element as mjsKey, or return NULL if the element is not an mjsKey.
.. _mjs_asMesh:
`mjs_asMesh <#mjs_asMesh>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_asMesh
Safely cast an element as mjsMesh, or return NULL if the element is not an mjsMesh.
.. _mjs_asHField:
`mjs_asHField <#mjs_asHField>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_asHField
Safely cast an element as mjsHField, or return NULL if the element is not an mjsHField.
.. _mjs_asSkin:
`mjs_asSkin <#mjs_asSkin>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_asSkin
Safely cast an element as mjsSkin, or return NULL if the element is not an mjsSkin.
.. _mjs_asTexture:
`mjs_asTexture <#mjs_asTexture>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_asTexture
Safely cast an element as mjsTexture, or return NULL if the element is not an mjsTexture.
.. _mjs_asMaterial:
`mjs_asMaterial <#mjs_asMaterial>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_asMaterial
Safely cast an element as mjsMaterial, or return NULL if the element is not an mjsMaterial.
.. _mjs_asPlugin:
`mjs_asPlugin <#mjs_asPlugin>`__
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. mujoco-include:: mjs_asPlugin
Safely cast an element as mjsPlugin, or return NULL if the element is not an mjsPlugin.
|