Skip to content
This repository
tree: 0304ea3d04
Fetching contributors…

Octocat-spinner-32-eaf2f5

Cannot retrieve contributors at this time

file 2618 lines (1994 sloc) 75.297 kb
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
#ifndef STG_H
#define STG_H
/*
* Stage : a multi-robot simulator. Part of the Player Project
*
* Copyright (C) 2001-2008 Richard Vaughan, Brian Gerkey, Andrew
* Howard, Toby Collett, Reed Hedges, Alex Couture-Beil, Jeremy
* Asher, Pooya Karimian
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program; if not, write to the Free Software
* Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*
*/

/* File: stage.h
* Desc: External header file for the Stage library
* Author: Richard Vaughan (vaughan@sfu.ca)
* Date: 1 June 2003
* CVS: $Id: stage.hh,v 1.15 2008-04-01 23:57:41 rtv Exp $
*/

/*! \file stage.h
Stage library header file

This header file contains the external interface for the Stage
library
*/

/**
\defgroup libstage libstage: the Stage Robot Simulation Library

Here is where I describe libstage for the developer.

*/
/*@{*/

#include <unistd.h>
#include <stdint.h> // for portable int types eg. uint32_t
#include <assert.h>
#include <math.h>
#include <stdlib.h>
#include <stdio.h>
#include <string.h>
#include <sys/types.h>
#include <sys/time.h>
#include <iostream>
#include <vector>

// we use GLib's data structures extensively. Perhaps we'll move to
// C++ STL types to lose this dependency one day.
#include <glib.h>

// FLTK Gui includes
#include <FL/Fl.H>
#include <FL/Fl_Box.H>
#include <FL/Fl_Gl_Window.H>
#include <FL/Fl_Menu_Bar.H>
#include <FL/Fl_Window.H>
#include <FL/fl_draw.H>
#include <FL/gl.h> // FLTK takes care of platform-specific GL stuff
//#include <FL/glut.H>

#ifdef __APPLE__
#include <OpenGL/glu.h>
#else
#include <GL/glu.h>
#endif

#include "option.hh"

/** The Stage library uses its own namespace */
namespace Stg
{
// foreward declare
class StgCanvas;
class Worldfile;
class StgWorld;
class StgWorldGui;
class StgModel;
class FileManager;
class OptionsDlg;
  
/** Initialize the Stage library */
void Init( int* argc, char** argv[] );

/** returns true iff Stg::Init() has been called. */
bool InitDone();
  
  /** Create unique identifying numbers for each type of model, and a
count of the number of types. */
  typedef enum {
MODEL_TYPE_PLAIN = 0,
MODEL_TYPE_LASER,
MODEL_TYPE_FIDUCIAL,
MODEL_TYPE_RANGER,
MODEL_TYPE_POSITION,
MODEL_TYPE_BLOBFINDER,
MODEL_TYPE_BLINKENLIGHT,
MODEL_TYPE_CAMERA,
MODEL_TYPE_COUNT // must be the last entry, to count the number of
// types
  } stg_model_type_t;


/// Copyright string
const char COPYRIGHT[] =
"Copyright Richard Vaughan and contributors 2000-2008";

/// Author string
const char AUTHORS[] =
"Richard Vaughan, Brian Gerkey, Andrew Howard, Reed Hedges, Pooya Karimian and contributors.";

/// Project website string
const char WEBSITE[] = "http://playerstage.org";

/// Project description string
const char DESCRIPTION[] =
"Robot simulation library\nPart of the Player Project";

/// Project distribution license string
const char LICENSE[] =
"Stage robot simulation library\n" \
"Copyright (C) 2000-2008 Richard Vaughan and contributors\n" \
"Part of the Player Project [http://playerstage.org]\n" \
"\n" \
"This program is free software; you can redistribute it and/or\n" \
"modify it under the terms of the GNU General Public License\n" \
"as published by the Free Software Foundation; either version 2\n" \
"of the License, or (at your option) any later version.\n" \
"\n" \
"This program is distributed in the hope that it will be useful,\n" \
"but WITHOUT ANY WARRANTY; without even the implied warranty of\n" \
"MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the\n" \
"GNU General Public License for more details.\n" \
"\n" \
"You should have received a copy of the GNU General Public License\n" \
"along with this program; if not, write to the Free Software\n" \
"Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, USA.\n" \
"\n" \
"The text of the license may also be available online at\n" \
"http://www.gnu.org/licenses/old-licenses/gpl-2.0.html\n";
  
/** The maximum length of a Stage model identifier string
*/
const uint32_t TOKEN_MAX = 64;

/** Convenient constant
*/
const double thousand = 1e3;

/** Convenient constant
*/
const double million = 1e6;

/** Convenient constant
*/
const double billion = 1e9;

/** convert an angle in radians to degrees
*/
inline double rtod( double r ){ return( r*180.0/M_PI ); }

/** convert an angle in degrees to radians
*/
inline double dtor( double d ){ return( d*M_PI/180.0 ); }

/** Normalize an angle to within +/_ M_PI
*/
inline double normalize( double a ){ return( atan2(sin(a), cos(a)));}

/** take binary sign of a, either -1, or 1 if >= 0
*/
inline int sgn( int a){ return( a<0 ? -1 : 1); }

/** take binary sign of a, either -1, or 1 if >= 0
*/
inline double sgn( double a){ return( a<0 ? -1.0 : 1.0); }

// forward declare
class StgModel;

/** Describe the image format used for saving screenshots
*/
typedef enum {
STG_IMAGE_FORMAT_PNG,
STG_IMAGE_FORMAT_JPG
} stg_image_format_t;

/** any integer value other than this is a valid fiducial ID
*/
enum { FiducialNone = 0 };

/** Value that Uniquely identifies a model
*/
typedef uint32_t stg_id_t;

/** Metres: floating point unit of distance
*/
typedef double stg_meters_t;

/** Radians: unit of angle
*/
typedef double stg_radians_t;

/** time structure */
typedef struct timeval stg_time_t;

/** Milliseconds: unit of (short) time */
typedef unsigned long stg_msec_t;

/** Microseconds: unit of (very short) time */
typedef uint64_t stg_usec_t;

/** Kilograms: unit of mass */
typedef double stg_kg_t; // Kilograms (mass)

/** Joules: unit of energy */
typedef double stg_joules_t;

/** Watts: unit of power (energy/time) */
typedef double stg_watts_t;

/** boolean */
typedef uint32_t stg_bool_t;

//typedef double stg_friction_t;

/** 32-bit ARGB color packed 0xAARRGGBB */
typedef uint32_t stg_color_t;

/** Specify a color from its components */
stg_color_t stg_color_pack( double r, double g, double b, double a );

/** Obtain the components of a color */
void stg_color_unpack( stg_color_t col,
double* r, double* g, double* b, double* a );

/** obstacle value. 0 means the model does not behave, or is sensed,
as an obstacle */
//typedef int stg_obstacle_return_t;

/** blobfinder return value. 0 means not detected by the
blobfinder */
//typedef int stg_blob_return_t;

/** fiducial return value. 0 means not detected as a fiducial */
//typedef int stg_fiducial_return_t;

//typedef int stg_ranger_return_t;

//typedef enum { STG_GRIP_NO = 0, STG_GRIP_YES } stg_gripper_return_t;

/** specify a rectangular size */
typedef struct
{
stg_meters_t x, y, z;
} stg_size_t;

/** Specify a 3 axis position, in x, y and heading. */
typedef struct
{
stg_meters_t x, y, z; //< location in 3 axes
stg_radians_t a; //< rotation about the z axis.
} stg_pose_t;

/** specify a 3 axis velocity in x, y and heading. */
typedef stg_pose_t stg_velocity_t;

/** specify an object's basic geometry: position and rectangular
size. */
typedef struct
{
stg_pose_t pose; //< position
stg_size_t size; //< extent
} stg_geom_t;

/** bound a range of values, from min to max */
typedef struct
{
double min; //< smallest value in range
double max; //< largest value in range
} stg_bounds_t;

/** bound a volume along the x,y,z axes */
typedef struct
{
stg_bounds_t x; //< volume extent along x axis
stg_bounds_t y; //< volume extent along y axis
stg_bounds_t z; //< volume extent along z axis
} stg_bounds3d_t;

/** bound a range of range values, from min to max
*/
typedef struct
{
stg_meters_t min; //< smallest value in range
stg_meters_t max; //< largest value in range
} stg_range_bounds_t;

/** define a three-dimensional bounding box */
typedef struct
{
stg_bounds_t x, y, z;
} stg_bbox3d_t;

/** define a field-of-view: an angle and range bounds */
typedef struct
{
stg_bounds_t range; //< min and max range of sensor
stg_radians_t angle; //< width of viewing angle of sensor
} stg_fov_t;


/** define a point on a 2d plane */
typedef struct
{
stg_meters_t x, y;
} stg_point_t;

/** define a point in 3d space */
typedef struct
{
float x, y, z;
} stg_vertex_t;

/** define vertex and its color */
typedef struct
{
float x, y, z, r, g, b, a;
} stg_colorvertex_t;

/** define a point in 3d space */
typedef struct
{
stg_meters_t x, y, z;
} stg_point3_t;

/** define an integer point on the plane
*/
typedef struct
{
int32_t x,y;
} stg_point_int_t;

/** Create an array of [count] points. Caller must free the returned
pointer, preferably with stg_points_destroy().
*/
stg_point_t* stg_points_create( size_t count );

/** frees a point array */
void stg_points_destroy( stg_point_t* pts );

/** create an array of 4 points containing the corners of a unit
square. */
stg_point_t* stg_unit_square_points_create();


/** matching function should return 0 iff the candidate block is
acceptable */
typedef int(*stg_line3d_func_t)(int32_t x, int32_t y, int32_t z,
void* arg );


/** Visit every voxel along a vector from (x,y,z) to (x+dx, y+dy, z+dz
). Call the function for every voxel, passing in the current voxel
coordinates followed by the two arguments. Adapted from Graphics
Gems IV, algorithm by Cohen & Kaufman 1991 */
int stg_line_3d( int32_t x, int32_t y, int32_t z,
int32_t dx, int32_t dy, int32_t dz,
stg_line3d_func_t visit_voxel,
void* arg );

/** Visit every voxel along a polygon defined by the array of
points. Calls stg_line_3d(). */
int stg_polygon_3d( stg_point_int_t* pts,
unsigned int pt_count,
stg_line3d_func_t visit_voxel,
void* arg );

  /** return a stg_pose_t with its fields initialized by the
parameters */
  stg_pose_t new_pose( stg_meters_t x, stg_meters_t y, stg_meters_t z, stg_radians_t a );

  /** return a random pose within the bounding rectangle, with z=0 and
angle random */
  stg_pose_t random_pose( stg_meters_t xmin, stg_meters_t xmax,
stg_meters_t ymin, stg_meters_t ymax );
  
const uint32_t STG_MOVE_TRANS = (1 << 0);
const uint32_t STG_MOVE_ROT = (1 << 1);
const uint32_t STG_MOVE_SCALE = (1 << 2);

typedef uint32_t stg_movemask_t;

const char STG_MP_PREFIX[] = "_mp_";
const char STG_MP_POSE[] = "_mp_pose";
const char STG_MP_VELOCITY[] = "_mp_velocity";
const char STG_MP_GEOM[] = "_mp_geom";
const char STG_MP_COLOR[] = "_mp_color";
const char STG_MP_WATTS[] = "_mp_watts";
const char STG_MP_FIDUCIAL_RETURN[] = "_mp_fiducial_return";
const char STG_MP_LASER_RETURN[] = "_mp_laser_return";
const char STG_MP_OBSTACLE_RETURN[] = "_mp_obstacle_return";
const char STG_MP_RANGER_RETURN[] = "_mp_ranger_return";
const char STG_MP_GRIPPER_RETURN[] = "_mp_gripper_return";
const char STG_MP_MASS[] = "_mp_mass";


/// laser return value
typedef enum
{
LaserTransparent, ///<not detected by laser model
LaserVisible, ///< detected by laser with a reflected intensity of 0
LaserBright ////< detected by laser with a reflected intensity of 1
} stg_laser_return_t;


namespace Draw
{
typedef struct {
double x, y, z;
} vertex_t;

typedef struct {
vertex_t min, max;
} bounds3_t;

typedef enum {
STG_D_DRAW_POINTS,
STG_D_DRAW_LINES,
STG_D_DRAW_LINE_STRIP,
STG_D_DRAW_LINE_LOOP,
STG_D_DRAW_TRIANGLES,
STG_D_DRAW_TRIANGLE_STRIP,
STG_D_DRAW_TRIANGLE_FAN,
STG_D_DRAW_QUADS,
STG_D_DRAW_QUAD_STRIP,
STG_D_DRAW_POLYGON,
STG_D_PUSH,
STG_D_POP,
STG_D_ROTATE,
STG_D_TRANSLATE,
} type_t;

/** the start of all stg_d structures looks like this */
typedef struct
{
type_t type;
} hdr_t;

/** push is just the header, but we define it for syntax checking */
typedef hdr_t push_t;
/** pop is just the header, but we define it for syntax checking */
typedef hdr_t pop_t;

/** stg_d draw command */
typedef struct
{
/** required type field */
type_t type;
/** number of vertices */
size_t vert_count;
/** array of vertex data follows at the end of this struct*/
vertex_t verts[];
} draw_t;

/** stg_d translate command */
typedef struct
{
/** required type field */
type_t type;
/** distance to translate, in 3 axes */
vertex_t vector;
} translate_t;

/** stg_d rotate command */
typedef struct
{
/** required type field */
type_t type;
/** vector about which we should rotate */
vertex_t vector;
/** angle to rotate */
stg_radians_t angle;
} rotate_t;

/** Create a draw_t object of specified type from a vertex array */
draw_t* create( type_t type,
vertex_t* verts,
size_t vert_count );

/** Delete the draw_t object, deallocting its memory */
void destroy( draw_t* d );
} // end namespace draw


// MACROS ------------------------------------------------------
// Some useful macros


/** Look up the color in the X11 database. (i.e. transform color
name to color value). If the color is not found in the
database, a bright red color (0xF00) will be returned instead.
*/
stg_color_t stg_lookup_color(const char *name);

/** calculate the sum of [p1] and [p2], in [p1]'s coordinate system, and
copy the result into result. */
void stg_pose_sum( stg_pose_t* result, stg_pose_t* p1, stg_pose_t* p2 );

/** returns the sum of [p1] + [p2], in [p1]'s coordinate system */
stg_pose_t pose_sum( stg_pose_t p1, stg_pose_t p2 );

// PRETTY PRINTING -------------------------------------------------

/** Report an error, with a standard, friendly message header */
void stg_print_err( const char* err );
/** Print human-readable geometry on stdout */
void stg_print_geom( stg_geom_t* geom );
/** Print human-readable pose on stdout */
void stg_print_pose( stg_pose_t* pose );
/** Print human-readable velocity on stdout */
void stg_print_velocity( stg_velocity_t* vel );

// const uint32_t STG_SHOW_BLOCKS = (1<<0);
// const uint32_t STG_SHOW_DATA = (1<<1);
// const uint32_t STG_SHOW_GEOM = (1<<2);
// const uint32_t STG_SHOW_GRID = (1<<3);
// const uint32_t STG_SHOW_OCCUPANCY = (1<<4);
// const uint32_t STG_SHOW_TRAILS = (1<<5);
// const uint32_t STG_SHOW_FOLLOW = (1<<6);
// const uint32_t STG_SHOW_CLOCK = (1<<7);
// const uint32_t STG_SHOW_QUADTREE = (1<<8);
// const uint32_t STG_SHOW_ARROWS = (1<<9);
// const uint32_t STG_SHOW_FOOTPRINT = (1<<10);
// const uint32_t STG_SHOW_BLOCKS_2D = (1<<10);
// const uint32_t STG_SHOW_TRAILRISE = (1<<11);
// const uint32_t STG_SHOW_STATUS = (1<<12);

// forward declare
class StgWorld;
class StgModel;


  /** A model creator function. Each model type must define a function of this type. */
  typedef StgModel* (*stg_creator_t)( StgWorld*, StgModel* );
  
typedef struct
{
const char* token;
stg_creator_t creator;
} stg_typetable_entry_t;
  
  /** a global (to the namespace) table mapping names to model types */
  extern stg_typetable_entry_t typetable[MODEL_TYPE_COUNT];

  void RegisterModel( stg_model_type_t type,
const char* name,
stg_creator_t creator );

  void RegisterModels();

void gl_draw_grid( stg_bounds3d_t vol );
void gl_pose_shift( stg_pose_t* pose );
void gl_coord_shift( double x, double y, double z, double a );

class StgFlag
{
public:
stg_color_t color;
double size;

StgFlag( stg_color_t color, double size );
StgFlag* Nibble( double portion );
};

/** Render a string at [x,y,z] in the current color */
void gl_draw_string( float x, float y, float z, const char *string);
void gl_speech_bubble( float x, float y, float z, const char* str );
void gl_draw_octagon( float w, float h, float m );

void stg_block_list_scale( GList* blocks,
stg_size_t* size );
void stg_block_list_destroy( GList* list );


typedef int(*stg_model_callback_t)(StgModel* mod, void* user );

// return val, or minval if val < minval, or maxval if val > maxval
double constrain( double val, double minval, double maxval );


/** container for a callback function and a single argument, so
they can be stored together in a list with a single pointer. */
typedef struct
{
stg_model_callback_t callback;
void* arg;
} stg_cb_t;

stg_cb_t* cb_create( stg_model_callback_t callback, void* arg );
void cb_destroy( stg_cb_t* cb );

typedef struct
{
StgModel* mod;
void* member;
char* name;
stg_model_callback_t callback_on;
stg_model_callback_t callback_off;
void* arg_on; // argument to callback_on
void* arg_off; // argument to callback_off
//int default_state; // disabled = 0
//GtkAction* action; // action associated with this toggle, may be NULL
char* path;
} stg_property_toggle_args_t;



/** defines a rectangle of [size] located at [pose] */
typedef struct
{
stg_pose_t pose;
stg_size_t size;
} stg_rotrect_t; // rotated rectangle

/** normalizes the set [rects] of [num] rectangles, so that they fit
exactly in a unit square.
*/
void stg_rotrects_normalize( stg_rotrect_t* rects, int num );

/** load the image file [filename] and convert it to an array of
rectangles, filling in the number of rects, width and
height. Memory is allocated for the rectangle array [rects], so
the caller must free [rects].
*/
int stg_rotrects_from_image_file( const char* filename,
stg_rotrect_t** rects,
unsigned int* rect_count,
unsigned int* widthp,
unsigned int* heightp );

// /** matching function should return 0 iff the candidate block is
// acceptable */
class StgBlock;

typedef bool (*stg_block_match_func_t)(StgBlock* candidate, StgModel* finder, const void* arg );

// TODO - some of this needs to be implemented, the rest junked.

/* // -------------------------------------------------------------- */

/* // standard energy consumption of some devices in W. */
/* // */
/* // The MOTIONKG value is a hack to approximate cost of motion, as */
/* // Stage does not yet have an acceleration model. */
/* // */
/* #define STG_ENERGY_COST_LASER 20.0 // 20 Watts! (LMS200 - from SICK web site) */
/* #define STG_ENERGY_COST_FIDUCIAL 10.0 // 10 Watts */
/* #define STG_ENERGY_COST_RANGER 0.5 // 500mW (estimate) */
/* #define STG_ENERGY_COST_MOTIONKG 10.0 // 10 Watts per KG when moving */
/* #define STG_ENERGY_COST_BLOB 4.0 // 4W (estimate) */

/* typedef struct */
/* { */
/* stg_joules_t joules; // current energy stored in Joules/1000 */
/* stg_watts_t watts; // current power expenditure in mW (mJoules/sec) */
/* int charging; // 1 if we are receiving energy, -1 if we are */
/* // supplying energy, 0 if we are neither charging nor */
/* // supplying energy. */
/* stg_meters_t range; // the range that our charging probe hit a charger */
/* } stg_energy_data_t; */

/* typedef struct */
/* { */
/* stg_joules_t capacity; // maximum energy we can store (we start fully charged) */
/* stg_meters_t probe_range; // the length of our recharge probe */
/* //stg_pose_t probe_pose; // TODO - the origin of our probe */

/* stg_watts_t give_rate; // give this many Watts to a probe that hits me (possibly 0) */

/* stg_watts_t trickle_rate; // this much energy is consumed or */
/* // received by this device per second as a */
/* // baseline trickle. Positive values mean */
/* // that the device is just burning energy */
/* // stayting alive, which is appropriate */
/* // for most devices. Negative values mean */
/* // that the device is receiving energy */
/* // from the environment, simulating a */
/* // solar cell or some other ambient energy */
/* // collector */

/* } stg_energy_config_t; */


/* // BLINKENLIGHT ------------------------------------------------------------ */

/* // a number of milliseconds, used for example as the blinkenlight interval */
/* #define STG_LIGHT_ON UINT_MAX */
/* #define STG_LIGHT_OFF 0 */

//typedef int stg_interval_ms_t;


/* // TOKEN ----------------------------------------------------------------------- */
/* // token stuff for parsing worldfiles - this may one day replace
the worldfile c++ code */

/* #define CFG_OPEN '(' */
/* #define CFG_CLOSE ')' */
/* #define STR_OPEN '\"' */
/* #define STR_CLOSE '\"' */
/* #define TPL_OPEN '[' */
/* #define TPL_CLOSE ']' */

/* typedef enum { */
/* STG_T_NUM = 0, */
/* STG_T_BOOLEAN, */
/* STG_T_MODELPROP, */
/* STG_T_WORLDPROP, */
/* STG_T_NAME, */
/* STG_T_STRING, */
/* STG_T_KEYWORD, */
/* STG_T_CFG_OPEN, */
/* STG_T_CFG_CLOSE, */
/* STG_T_TPL_OPEN, */
/* STG_T_TPL_CLOSE, */
/* } stg_token_type_t; */




/* typedef struct stg_token */
/* { */
/* char* token; ///< the text of the token */
/* stg_token_type_t type; ///< the type of the token */
/* unsigned int line; ///< the line on which the token appears */

/* struct stg_token* next; ///< linked list support */
/* struct stg_token* child; ///< tree support */

/* } stg_token_t; */

/* stg_token_t* stg_token_next( stg_token_t* tokens ); */
/* /// print [token] formatted for a human reader, with a string [prefix] */
/* void stg_token_print( char* prefix, stg_token_t* token ); */

/* /// print a token array suitable for human reader */
/* void stg_tokens_print( stg_token_t* tokens ); */
/* void stg_tokens_free( stg_token_t* tokens ); */

/* /// create a new token structure from the arguments */
/* stg_token_t* stg_token_create( const char* token, stg_token_type_t type, int line ); */

/* /// add a token to a list */
/* stg_token_t* stg_token_append( stg_token_t* head, */
/* char* token, stg_token_type_t type, int line ); */

/* const char* stg_token_type_string( stg_token_type_t type ); */

/* const char* stg_model_type_string( stg_model_type_t type ); */

/* // functions for parsing worldfiles */
/* stg_token_t* stg_tokenize( FILE* wf ); */
/* //StgWorld* sc_load_worldblock( stg_client_t* cli, stg_token_t** tokensptr ); */
/* //stg_model_t* sc_load_modelblock( StgWorld* world, stg_model_t* parent, */
/* // stg_token_t** tokensptr ); */




//#ifdef __cplusplus
//}
//#endif


// list iterator macros
#define LISTFUNCTION( LIST, TYPE, FUNC ) for( GList* it=LIST; it; it=it->next ) FUNC((TYPE)it->data);

#define LISTMETHOD( LIST, TYPE, METHOD ) for( GList* it=LIST; it; it=it->next ) ((TYPE)it->data)->METHOD();

#define LISTFUNCTIONARG( LIST, TYPE, FUNC, ARG ) for( GList* it=LIST; it; it=it->next ) FUNC((TYPE)it->data, ARG);

#define LISTMETHODARG( LIST, TYPE, METHOD, ARG ) for( GList* it=LIST; it; it=it->next ) ((TYPE)it->data)->METHOD(ARG);


// Error macros - output goes to stderr
#define PRINT_ERR(m) fprintf( stderr, "\033[41merr\033[0m: "m" (%s %s)\n", __FILE__, __FUNCTION__)
#define PRINT_ERR1(m,a) fprintf( stderr, "\033[41merr\033[0m: "m" (%s %s)\n", a, __FILE__, __FUNCTION__)
#define PRINT_ERR2(m,a,b) fprintf( stderr, "\033[41merr\033[0m: "m" (%s %s)\n", a, b, __FILE__, __FUNCTION__)
#define PRINT_ERR3(m,a,b,c) fprintf( stderr, "\033[41merr\033[0m: "m" (%s %s)\n", a, b, c, __FILE__, __FUNCTION__)
#define PRINT_ERR4(m,a,b,c,d) fprintf( stderr, "\033[41merr\033[0m: "m" (%s %s)\n", a, b, c, d, __FILE__, __FUNCTION__)
#define PRINT_ERR5(m,a,b,c,d,e) fprintf( stderr, "\033[41merr\033[0m: "m" (%s %s)\n", a, b, c, d, e, __FILE__, __FUNCTION__)

// Warning macros
#define PRINT_WARN(m) printf( "\033[44mwarn\033[0m: "m" (%s %s)\n", __FILE__, __FUNCTION__)
#define PRINT_WARN1(m,a) printf( "\033[44mwarn\033[0m: "m" (%s %s)\n", a, __FILE__, __FUNCTION__)
#define PRINT_WARN2(m,a,b) printf( "\033[44mwarn\033[0m: "m" (%s %s)\n", a, b, __FILE__, __FUNCTION__)
#define PRINT_WARN3(m,a,b,c) printf( "\033[44mwarn\033[0m: "m" (%s %s)\n", a, b, c, __FILE__, __FUNCTION__)
#define PRINT_WARN4(m,a,b,c,d) printf( "\033[44mwarn\033[0m: "m" (%s %s)\n", a, b, c, d, __FILE__, __FUNCTION__)
#define PRINT_WARN5(m,a,b,c,d,e) printf( "\033[44mwarn\033[0m: "m" (%s %s)\n", a, b, c, d, e, __FILE__, __FUNCTION__)

// Message macros
#ifdef DEBUG
#define PRINT_MSG(m) printf( "Stage: "m" (%s %s)\n", __FILE__, __FUNCTION__)
#define PRINT_MSG1(m,a) printf( "Stage: "m" (%s %s)\n", a, __FILE__, __FUNCTION__)
#define PRINT_MSG2(m,a,b) printf( "Stage: "m" (%s %s)\n", a, b, __FILE__, __FUNCTION__)
#define PRINT_MSG3(m,a,b,c) printf( "Stage: "m" (%s %s)\n", a, b, c, __FILE__, __FUNCTION__)
#define PRINT_MSG4(m,a,b,c,d) printf( "Stage: "m" (%s %s)\n", a, b, c, d, __FILE__, __FUNCTION__)
#define PRINT_MSG5(m,a,b,c,d,e) printf( "Stage: "m" (%s %s)\n", a, b, c, d, e,__FILE__, __FUNCTION__)
#else
#define PRINT_MSG(m) printf( "Stage: "m"\n" )
#define PRINT_MSG1(m,a) printf( "Stage: "m"\n", a)
#define PRINT_MSG2(m,a,b) printf( "Stage: "m"\n,", a, b )
#define PRINT_MSG3(m,a,b,c) printf( "Stage: "m"\n", a, b, c )
#define PRINT_MSG4(m,a,b,c,d) printf( "Stage: "m"\n", a, b, c, d )
#define PRINT_MSG5(m,a,b,c,d,e) printf( "Stage: "m"\n", a, b, c, d, e )
#endif

// DEBUG macros
#ifdef DEBUG
#define PRINT_DEBUG(m) printf( "debug: "m" (%s %s)\n", __FILE__, __FUNCTION__)
#define PRINT_DEBUG1(m,a) printf( "debug: "m" (%s %s)\n", a, __FILE__, __FUNCTION__)
#define PRINT_DEBUG2(m,a,b) printf( "debug: "m" (%s %s)\n", a, b, __FILE__, __FUNCTION__)
#define PRINT_DEBUG3(m,a,b,c) printf( "debug: "m" (%s %s)\n", a, b, c, __FILE__, __FUNCTION__)
#define PRINT_DEBUG4(m,a,b,c,d) printf( "debug: "m" (%s %s)\n", a, b, c ,d, __FILE__, __FUNCTION__)
#define PRINT_DEBUG5(m,a,b,c,d,e) printf( "debug: "m" (%s %s)\n", a, b, c ,d, e, __FILE__, __FUNCTION__)
#else
#define PRINT_DEBUG(m)
#define PRINT_DEBUG1(m,a)
#define PRINT_DEBUG2(m,a,b)
#define PRINT_DEBUG3(m,a,b,c)
#define PRINT_DEBUG4(m,a,b,c,d)
#define PRINT_DEBUG5(m,a,b,c,d,e)
#endif

class StgBlock;
class StgModel;


stg_msec_t stg_realtime();
stg_msec_t stg_realtime_since_start( void );



// ANCESTOR CLASS

/** Define a callback function type that can be attached to a
record within a model and called whenever the record is set.*/
typedef int (*stg_model_callback_t)( StgModel* mod, void* user );


/** Base class for StgModel and StgWorld */
class StgAncestor
{
friend class StgCanvas; // allow StgCanvas access to our private members

protected:
GList* children;
  //GHashTable* child_types;
  

char* token;
bool debug;

public:

  /** array contains the number of each type of child model */
  unsigned int child_type_counts[MODEL_TYPE_COUNT];

StgAncestor();
virtual ~StgAncestor();

  // unsigned int GetNumChildrenOfType( const char* typestr );
  // void IncrementNumChildrenOfType( const char* typestr );

virtual void AddChild( StgModel* mod );
virtual void RemoveChild( StgModel* mod );
virtual stg_pose_t GetGlobalPose();

const char* Token()
{ return this->token; }

  void SetToken( const char* str )
  {
this->token = strdup( str );
  }
  
// PURE VIRTUAL - descendents must implement
virtual void PushColor( stg_color_t col ) = 0;
virtual void PushColor( double r, double g, double b, double a ) = 0;
virtual void PopColor() = 0; // does nothing
};


typedef struct
{
int enabled;
stg_pose_t pose;
stg_meters_t size; ///< rendered as a sphere with this diameter
stg_color_t color;
stg_msec_t period; ///< duration of a complete cycle
double duty_cycle; ///< mark/space ratio
} stg_blinkenlight_t;

typedef struct
{
uint32_t counter;
GSList** lists;
} stg_bigblock_t;

typedef struct
{
StgWorld* world;
StgBlock* block;
} stg_render_info_t;


class StgBlockGrid
{
private:
//stg_bigblock_t* map;
GSList** cells;

//GTrashStack* trashstack;
uint32_t width, height;// bwidth, bheight;

public:
//uint32_t numbits;
StgBlockGrid( uint32_t width, uint32_t height );
~StgBlockGrid();
void AddBlock( uint32_t x, uint32_t y, StgBlock* block );
void RemoveBlock( uint32_t x, uint32_t y, StgBlock* block );
GSList* GetList( uint32_t x, uint32_t y );
void GlobalRemoveBlock( StgBlock* block );
void Draw( bool drawall );

/** Returns the number of blocks occupying the big block, specified
in big block coordinates, NOT in small blocks.*/
//uint32_t BigBlockOccupancy( uint32_t bbx, uint32_t bby );
};

/** raytrace sample
*/
typedef struct
{
stg_pose_t pose; ///< location and direction of the ray origin
stg_meters_t range; ///< range to beam hit in meters
StgBlock* block; ///< the block struck by this beam
} stg_raytrace_sample_t;


const uint32_t INTERVAL_LOG_LEN = 32;

class Region;
class SuperRegion;

/** WORLD CLASS */
class StgWorld : public StgAncestor
{
friend class StgModel; // allow access to private members
friend class StgBlock;
friend class StgTime;
   friend class StgCanvas;

public:
  static void UpdateAll();
  
private:

  static GList* world_list;
  /** Update all existing worlds */


static bool quit_all; // quit all worlds ASAP
static unsigned int next_id; //< initialized to zero, used tob
//allocate unique sequential world ids
static int AddBlockPixel( int x, int y, int z,
stg_render_info_t* rinfo ) ; //< used as a callback by StgModel

  //stg_usec_t real_time_next_update;
stg_usec_t real_time_start;

bool quit; // quit this world ASAP

// convert a distance in meters to a distance in world occupancy grid pixels
int32_t MetersToPixels( stg_meters_t x ){ return (int32_t)floor(x * ppm) ; };

  void Initialize( const char* token,
stg_msec_t interval_sim,
double ppm );
  
virtual void PushColor( stg_color_t col ) { /* do nothing */ };
virtual void PushColor( double r, double g, double b, double a ) { /* do nothing */ };
virtual void PopColor(){ /* do nothing */ };

stg_usec_t real_time_now;

/** StgWorld::quit is set true when this simulation time is reached */
stg_usec_t quit_time;

bool destroy;

  //stg_id_t id;

//GHashTable* models_by_id; ///< the models that make up the world, indexed by id
GHashTable* models_by_name; ///< the models that make up the world, indexed by name
GList* velocity_list; ///< a list of models that have non-zero velocity, for efficient updating

  //stg_usec_t wall_last_update; ///< the real time of the last update in ms

bool dirty; ///< iff true, a gui redraw would be required


int total_subs; ///< the total number of subscriptions to all models
double ppm; ///< the resolution of the world model in pixels per meter

void StartUpdatingModel( StgModel* mod );
void StopUpdatingModel( StgModel* mod );

SuperRegion* CreateSuperRegion( int32_t x, int32_t y );
void DestroySuperRegion( SuperRegion* sr );

void Raytrace( stg_pose_t pose,
stg_meters_t range,
stg_block_match_func_t func,
StgModel* finder,
const void* arg,
stg_raytrace_sample_t* sample,
bool ztest );

void Raytrace( stg_pose_t pose,
stg_meters_t range,
stg_radians_t fov,
stg_block_match_func_t func,
StgModel* finder,
const void* arg,
stg_raytrace_sample_t* samples,
uint32_t sample_count,
bool ztest );

void RemoveBlock( int x, int y, StgBlock* block );

protected:
GHashTable* superregions;
GList* update_list; //< the descendants that need Update() called
stg_usec_t interval_sim; ///< temporal resolution: milliseconds that elapse between simulated time steps

static void UpdateCb( StgWorld* world);

  stg_usec_t sim_time; ///< the current sim time in this world in ms
  
GList* ray_list;
// store rays traced for debugging purposes
void RecordRay( double x1, double y1, double x2, double y2 );
Worldfile* wf; ///< If set, points to the worldfile used to create this world
bool graphics;
stg_bounds3d_t extent;

/** Enlarge the bounding volume to include this point */
void Extend( stg_point3_t pt );

//GHashTable* blocks;
GArray lines;

virtual void AddModel( StgModel* mod );
virtual void RemoveModel( StgModel* mod );

GList* GetRayList(){ return ray_list; };
void ClearRays();

long unsigned int updates; ///< the number of simulated time steps executed so far

public:
  static const int DEFAULT_PPM = 50; // default resolution in pixels per meter
  static const stg_msec_t DEFAULT_INTERVAL_SIM = 100; ///< duration of sim timestep
  
StgWorld( const char* token = "MyWorld",
stg_msec_t interval_sim = DEFAULT_INTERVAL_SIM,
double ppm = DEFAULT_PPM );

virtual ~StgWorld();

  FileManager* fileMan;

stg_usec_t SimTimeNow(void){ return sim_time;} ;
stg_usec_t RealTimeNow(void);
stg_usec_t RealTimeSinceStart(void);
  //void PauseUntilNextUpdateTime(void);
  // void IdleUntilNextUpdateTime( int (*idler)(void) );

void AddBlock( StgBlock* block );
void RemoveBlock( StgBlock* block );

stg_usec_t GetSimInterval(){ return interval_sim; };

Worldfile* GetWorldFile(){ return wf; };

virtual void Load( const char* worldfile_path );
virtual void UnLoad();
virtual void Reload();
virtual bool Save( const char* filename );
virtual bool Update(void);

bool TestQuit(){ return( quit || quit_all ); }
void Quit(){ quit = true; }
void QuitAll(){ quit_all = true; }
void CancelQuit(){ quit = false; }
void CancelQuitAll(){ quit_all = false; }

  /** Get the resolution in pixels-per-metre of the underlying
discrete raytracing model */
double Resolution(){ return ppm; };

  /** Returns a pointer to the model identified by ID, or NULL if
nonexistent */
  //StgModel* GetModel( const stg_id_t id );

  /** Returns a pointer to the model identified by name, or NULL if
nonexistent */
StgModel* GetModel( const char* name );

  /** Return the 3D bounding box of the world, in meters */
  stg_bounds3d_t GetExtent(){ return extent; };

  /** call func( model, arg ) for each model in the world */
void ForEachModel( GHFunc func, void* arg )
{ g_hash_table_foreach( models_by_name, func, arg ); };

  /** Return the number of times the world has been updated. */
long unsigned int GetUpdateCount()
{ return updates; }
};


typedef struct {
stg_pose_t pose;
stg_color_t color;
stg_usec_t time;
} stg_trail_item_t;

typedef int ctrlinit_t( StgModel* mod );
//typedef void ctrlupdate_t( StgModel* mod );

// MODEL CLASS
class StgModel : public StgAncestor
{
friend class StgAncestor;
friend class StgWorld;
friend class StgWorldGui;
friend class StgCanvas;
  
private:
  /** the number of models instatiated - used to assign unique IDs */
  static uint32_t count;
  static GHashTable* modelsbyid;

  std::vector<Option*> drawOptions;

public:
  /** Look up a model pointer by a unique model ID */
  static StgModel* LookupId( uint32_t id )
  {
return (StgModel*)g_hash_table_lookup( modelsbyid, (void*)id );
  }
  
  /** unique process-wide identifier for this model */
  uint32_t id;

protected:
  stg_pose_t pose;
stg_velocity_t velocity;
stg_watts_t watts; //< power consumed by this model
stg_color_t color;
stg_kg_t mass;
stg_geom_t geom;
stg_laser_return_t laser_return;
int obstacle_return;
int blob_return;
int gripper_return;
int ranger_return;
int fiducial_return;
int fiducial_key;
int boundary;
stg_meters_t map_resolution;
stg_bool_t stall;

/** if non-null, this string is displayed in the GUI */
char* say_string;

bool on_velocity_list;

int gui_nose;
int gui_grid;
int gui_outline;
int gui_mask;

/// Register an Option for pickup by the GUI
void registerOption( Option* opt ) { drawOptions.push_back( opt ); }


StgModel* parent; //< the model that owns this one, possibly NULL

/** GData datalist can contain arbitrary named data items. Can be used
by derived model types to store properties, and for user code
to associate arbitrary items with a model. */
GData* props;

/** callback functions can be attached to any field in this
structure. When the internal function model_change(<mod>,<field>)
is called, the callback is triggered */
GHashTable* callbacks;

int subs; //< the number of subscriptions to this model

stg_usec_t interval; //< time between updates in ms
stg_usec_t last_update; //< time of last update in ms

stg_bool_t disabled; //< if non-zero, the model is disabled

  // GList* d_list;
GList* blocks; //< list of stg_block_t structs that comprise a body

GArray* trail;

bool rebuild_displaylist; //< iff true, regenerate block display list before redraw

stg_pose_t global_pose;

bool gpose_dirty; //< set this to indicate that global pose may have
//changed

bool data_fresh; ///< this can be set to indicate that the model has
///new data that may be of interest to users. This
///allows polling the model instead of adding a
///data callback.

//stg_id_t id; // globally unique ID used as hash table key and
// worldfile section identifier

StgWorld* world; // pointer to the world in which this model exists
  
  /** Check to see if the given change in pose will yield a collision
with obstacles. Returns a pointer to the first entity we are in
collision with, and stores the location of the hit in hitx,hity (if
non-null) Returns NULL if no collision. */
  StgModel* TestCollision( stg_pose_t pose,
stg_meters_t* hitx,
stg_meters_t* hity );
  
  /** Check to see if the current pose is in a collision
with obstacles. Returns a pointer to the first entity we are in
collision with, and stores the location of the hit in hitx,hity (if
non-null) Returns NULL if no collision. */
  StgModel* TestCollision( stg_meters_t* hitx,
stg_meters_t* hity );
  
public: void PlaceInFreeSpace( stg_meters_t xmin, stg_meters_t xmax,
stg_meters_t ymin, stg_meters_t ymax );
  
protected:
void Map();
void UnMap();

void MapWithChildren();
void UnMapWithChildren();

int TreeToPtrArray( GPtrArray* array );


/** raytraces a single ray from the point and heading identified by
pose, in local coords */
void Raytrace( stg_pose_t pose,
stg_meters_t range,
stg_block_match_func_t func,
const void* arg,
stg_raytrace_sample_t* sample,
bool ztest = true );

/** raytraces multiple rays around the point and heading identified
by pose, in local coords */
void Raytrace( stg_pose_t pose,
stg_meters_t range,
stg_radians_t fov,
stg_block_match_func_t func,
const void* arg,
stg_raytrace_sample_t* samples,
uint32_t sample_count,
bool ztest = true );

void Raytrace( stg_radians_t bearing,
stg_meters_t range,
stg_block_match_func_t func,
const void* arg,
stg_raytrace_sample_t* sample,
bool ztest = true );

void Raytrace( stg_radians_t bearing,
stg_meters_t range,
stg_radians_t fov,
stg_block_match_func_t func,
const void* arg,
stg_raytrace_sample_t* samples,
uint32_t sample_count,
bool ztest = true );


/** Causes this model and its children to recompute their global
position instead of using a cached pose in
StgModel::GetGlobalPose()..*/
void GPoseDirtyTree();

virtual void Startup();
virtual void Shutdown();
virtual void Update();
virtual void UpdatePose();

void DrawBlocksTree();
virtual void DrawBlocks();
virtual void DrawStatus( StgCanvas* canvas );
void DrawStatusTree( StgCanvas* canvas );

  void PushLocalCoords();
   void PopCoords();

///Draw the image stored in texture_id above the model
void DrawImage( uint32_t texture_id, Stg::StgCanvas* canvas, float alpha );


// static wrapper for DrawBlocks()
static void DrawBlocks( gpointer dummykey,
StgModel* mod,
void* arg );

virtual void DrawPicker();
virtual void DataVisualize();

virtual void DrawSelected(void);

void DrawTrailFootprint();
void DrawTrailBlocks();
void DrawTrailArrows();
void DrawGrid();
void UpdateIfDue();
  
  /* hooks for attaching special callback functions (not used as
variables) */
  char startup_hook, shutdown_hook, load_hook, save_hook, update_hook;
  
  ctrlinit_t* initfunc;
  
  GList* flag_list;
  
  Worldfile* wf;
  int wf_entity;
  
  GPtrArray* blinkenlights;
  void DrawBlinkenlights();

  /** OpenGL display list identifier */
  int blocks_dl;

  /** Compile the display list for this model */
  //void BuildDisplayList();
  
  stg_model_type_t type;

  void DataVisualizeTree();

public:

  static const char* typestr;

// constructor
  StgModel( StgWorld* world, StgModel* parent, stg_model_type_t type = MODEL_TYPE_PLAIN );

// destructor
virtual ~StgModel();

void Say( const char* str );

  /** Set the worldfile and worldfile entity ID - must be called
before Load() */
  void Load( Worldfile* wf, int wf_entity )
  {
SetWorldfile( wf, wf_entity );
Load(); // call virtual load
  }

  /** Set the worldfile and worldfile entity ID */
  void SetWorldfile( Worldfile* wf, int wf_entity )
  { this->wf = wf; this->wf_entity = wf_entity; }
  
  /** configure a model by reading from the current world file */
   virtual void Load();
  
/** save the state of the model to the current world file */
virtual void Save();

/** Should be called after all models are loaded, to do any last-minute setup */
void Init();


void AddFlag( StgFlag* flag );
void RemoveFlag( StgFlag* flag );

void PushFlag( StgFlag* flag );
StgFlag* PopFlag();

int GetFlagCount(){ return g_list_length( flag_list ); }

void DrawFlagList();

void AddBlinkenlight( stg_blinkenlight_t* b )
{
g_ptr_array_add( this->blinkenlights, b );
}

void ClearBlinkenlights()
{
g_ptr_array_set_size( this->blinkenlights, 0 );
}

virtual void PushColor( stg_color_t col )
{ world->PushColor( col ); }

virtual void PushColor( double r, double g, double b, double a )
{ world->PushColor( r,g,b,a ); }

virtual void PopColor(){ world->PopColor(); }

void Enable(){ disabled = false; };
void Disable(){ disabled = true; };

// Load a control program for this model from an external library
void LoadControllerModule( char* lib );

// call this to ensure the GUI window is redrawn
void NeedRedraw();

void AddBlock( stg_point_t* pts,
size_t pt_count,
stg_meters_t zmin,
stg_meters_t zmax,
stg_color_t color,
bool inherit_color );

void AddBlockRect( double x, double y,
double width, double height );

/** remove all blocks from this model, freeing their memory */
void ClearBlocks();

  //const char* TypeStr(){ return this->typestr; }
StgModel* Parent(){ return this->parent; }
StgModel* GetModel( const char* name );
bool Stall(){ return this->stall; }
int GuiMask(){ return this->gui_mask; };
inline StgWorld* GetWorld(){ return this->world; }

/// return the root model of the tree containing this model
StgModel* Root()
{ return( parent ? parent->Root() : this ); }

bool ObstacleReturn(){ return obstacle_return; }
stg_laser_return_t GetLaserReturn(){ return laser_return; }
int GetRangerReturn(){ return ranger_return; }
int FiducialReturn(){ return fiducial_return; }
int FiducialKey(){ return fiducial_key; }

bool IsAntecedent( StgModel* testmod );

// returns true if model [testmod] is a descendent of model [mod]
bool IsDescendent( StgModel* testmod );

bool IsRelated( StgModel* mod2 );

/** get the pose of a model in the global CS */
stg_pose_t GetGlobalPose();

/** get the velocity of a model in the global CS */
stg_velocity_t GetGlobalVelocity();

/* set the velocity of a model in the global coordinate system */
void SetGlobalVelocity( stg_velocity_t gvel );

/** subscribe to a model's data */
void Subscribe();

/** unsubscribe from a model's data */
void Unsubscribe();

/** set the pose of model in global coordinates */
void SetGlobalPose( stg_pose_t gpose );

/** set a model's velocity in its parent's coordinate system */
void SetVelocity( stg_velocity_t vel );

/** set a model's pose in its parent's coordinate system */
void SetPose( stg_pose_t pose );

/** add values to a model's pose in its parent's coordinate system */
void AddToPose( stg_pose_t pose );

/** add values to a model's pose in its parent's coordinate system */
void AddToPose( double dy, double dy, double dz, double da );

/** set a model's geometry (size and center offsets) */
void SetGeom( stg_geom_t src );

/** set a model's geometry (size and center offsets) */
void SetFiducialReturn( int fid );

/** set a model's fiducial key: only fiducial finders with a
matching key can detect this model as a fiducial. */
void SetFiducialKey( int key );

stg_color_t GetColor(){ return color; }

// stg_laser_return_t GetLaserReturn(){ return laser_return; }

/** Change a model's parent - experimental*/
int SetParent( StgModel* newparent);

/** Get a model's geometry - it's size and local pose (offset from
origin in local coords) */
stg_geom_t GetGeom(){ return geom; }

/** Get the pose of a model in its parent's coordinate system */
stg_pose_t GetPose(){ return pose; }

/** Get a model's velocity (in its local reference frame) */
stg_velocity_t GetVelocity(){ return velocity; }

// guess what these do?
void SetColor( stg_color_t col );
void SetMass( stg_kg_t mass );
void SetStall( stg_bool_t stall );
void SetGripperReturn( int val );
void SetLaserReturn( stg_laser_return_t val );
void SetObstacleReturn( int val );
void SetBlobReturn( int val );
void SetRangerReturn( int val );
void SetBoundary( int val );
void SetGuiNose( int val );
void SetGuiMask( int val );
void SetGuiGrid( int val );
void SetGuiOutline( int val );
void SetWatts( stg_watts_t watts );
void SetMapResolution( stg_meters_t res );

bool DataIsFresh(){ return this->data_fresh; }

/* attach callback functions to data members. The function gets
called when the member is changed using SetX() accessor method */

void AddCallback( void* address,
stg_model_callback_t cb,
void* user );

int RemoveCallback( void* member,
stg_model_callback_t callback );

void CallCallbacks( void* address );

/* wrappers for the generic callback add & remove functions that hide
some implementation detail */

void AddStartupCallback( stg_model_callback_t cb, void* user )
{ AddCallback( &startup_hook, cb, user ); };

void RemoveStartupCallback( stg_model_callback_t cb )
{ RemoveCallback( &startup_hook, cb ); };

void AddShutdownCallback( stg_model_callback_t cb, void* user )
{ AddCallback( &shutdown_hook, cb, user ); };

void RemoveShutdownCallback( stg_model_callback_t cb )
{ RemoveCallback( &shutdown_hook, cb ); }

void AddLoadCallback( stg_model_callback_t cb, void* user )
{ AddCallback( &load_hook, cb, user ); }

void RemoveLoadCallback( stg_model_callback_t cb )
{ RemoveCallback( &load_hook, cb ); }

void AddSaveCallback( stg_model_callback_t cb, void* user )
{ AddCallback( &save_hook, cb, user ); }

void RemoveSaveCallback( stg_model_callback_t cb )
{ RemoveCallback( &save_hook, cb ); }

void AddUpdateCallback( stg_model_callback_t cb, void* user )
{ AddCallback( &update_hook, cb, user ); }

void RemoveUpdateCallback( stg_model_callback_t cb )
{ RemoveCallback( &update_hook, cb ); }

/** named-property interface
*/
void* GetProperty( char* key );

/** @brief Set a named property of a Stage model.

Set a property of a Stage model.

This function can set both predefined and user-defined
properties of a model. Predefined properties are intrinsic to
every model, such as pose and color. Every supported predefined
properties has its identifying string defined as a preprocessor
macro in stage.h. Users should use the macro instead of a
hard-coded string, so that the compiler can help you to avoid
mis-naming properties.

User-defined properties allow the user to attach arbitrary data
pointers to a model. User-defined property data is not copied,
so the original pointer must remain valid. User-defined property
names are simple strings. Names beginning with an underscore
('_') are reserved for internal libstage use: users should not
use names beginning with underscore (at risk of causing very
weird behaviour).

Any callbacks registered for the named property will be called.

Returns 0 on success, or a positive error code on failure.

*CAUTION* The caller is responsible for making sure the pointer
points to data of the correct type for the property, so use
carefully. Check the docs or the equivalent
stg_model_set_<property>() function definition to see the type
of data required for each property.
*/
int SetProperty( char* key, void* data );
void UnsetProperty( char* key );


void AddPropertyToggles( void* member,
stg_model_callback_t callback_on,
void* arg_on,
stg_model_callback_t callback_off,
void* arg_off,
char* name,
char* label,
gboolean enabled );

virtual void Print( char* prefix );
virtual const char* PrintWithPose();

/** Convert a pose in the world coordinate system into a model's
local coordinate system. Overwrites [pose] with the new
coordinate. */
void GlobalToLocal( stg_pose_t* pose );

/** Convert a pose in the model's local coordinate system into the
world coordinate system. Overwrites [pose] with the new
coordinate. */
//void LocalToGlobal( stg_pose_t* pose );

/** Return the global pose (i.e. pose in world coordinates) of a
pose specified in the model's local coordinate system */
stg_pose_t LocalToGlobal( stg_pose_t pose );

/** Return the 3d point in world coordinates of a 3d point
specified in the model's local coordinate system */
stg_point3_t LocalToGlobal( stg_point3_t local );

/** returns the first descendent of this model that is unsubscribed
and has the type indicated by the string */
StgModel* GetUnsubscribedModelOfType( stg_model_type_t type );

// iff true, model may output some debugging visualizations and other info
//bool debug;

const std::vector<Option*>& getOptions() const { return drawOptions; }
};

// BLOCKS
class StgBlock
{
public:

/** Block Constructor. A model's body is a list of these
blocks. The point data is copied, so pts can safely be freed
after constructing the block.*/
StgBlock( StgModel* mod,
stg_point_t* pts,
size_t pt_count,
stg_meters_t height,
stg_meters_t z_offset,
stg_color_t color,
bool inherit_color );

~StgBlock();

void Map();
void UnMap(); // draw the block into the world

void DrawGlobal(); // draw the block in OpenGL using pts_global coords
void Draw(); // draw the block in OpenGL
//void Draw2D(); // draw the block in OpenGL
void DrawSolid(); // draw the block in OpenGL as a solid single color
void DrawFootPrint(); // draw the projection of the block onto the z=0 plane

static void ScaleList( GList* blocks, stg_size_t* size );
void RecordRenderPoint( GSList** head, GSList* link, unsigned int* c1, unsigned int* c2 );

StgModel* Model(){ return mod; };

stg_point_t* Points( unsigned int *count )
{ if( count ) *count = pt_count; return pts; };

bool IntersectGlobalZ( stg_meters_t z )
{ return( z >= global_zmin && z <= global_zmax ); }

stg_color_t Color()
{ return( inherit_color ? mod->GetColor() : color ); }

private:
stg_point_t* pts; //< points defining a polygon
size_t pt_count; //< the number of points
stg_meters_t zmin;
stg_meters_t zmax;

stg_meters_t global_zmin;
stg_meters_t global_zmax;

StgModel* mod; //< model to which this block belongs

stg_point_int_t* pts_global_pixels; //< points defining a polygon in global coords

stg_color_t color;
bool inherit_color;

GArray* rendered_points;

inline void DrawTop();
inline void DrawSides();

inline void PushColor( stg_color_t col )
{ mod->PushColor( col ); }

inline void PushColor( double r, double g, double b, double a )
{ mod->PushColor( r,g,b,a ); }

inline void PopColor()
{ mod->PopColor(); }
};

// COLOR STACK CLASS
class GlColorStack
{
public:
GlColorStack();
~GlColorStack();

void Push( GLdouble col[4] );
void Push( double r, double g, double b, double a );
void Push( double r, double g, double b );
void Push( stg_color_t col );

void Pop();

unsigned int Length()
{ return g_queue_get_length( colorstack ); }

private:
GQueue* colorstack;
};

class StgCamera
{
protected:
float _pitch; //left-right (about y)
float _yaw; //up-down (about x)
float _x, _y, _z;

public:
StgCamera() : _pitch( 0 ), _yaw( 0 ), _x( 0 ), _y( 0 ), _z( 0 ) { }
virtual ~StgCamera() { }

virtual void Draw( void ) const = 0;
virtual void SetProjection( void ) const = 0;

inline float yaw( void ) const { return _yaw; }
inline float pitch( void ) const { return _pitch; }

inline float x( void ) const { return _x; }
inline float y( void ) const { return _y; }
inline float z( void ) const { return _z; }

//TODO data should be passed in somehow else. (at least min/max stuff)
//virtual void SetProjection( float pixels_width, float pixels_height, float y_min, float y_max ) const = 0;
};

class StgPerspectiveCamera : public StgCamera
{
private:
float _z_near;
float _z_far;
float _vert_fov;
float _horiz_fov;
float _aspect;

public:
StgPerspectiveCamera( void );

virtual void Draw( void ) const;
virtual void SetProjection( void ) const;
//void SetProjection( float aspect ) const;
void update( void );

void strafe( float amount );
void forward( float amount );

inline void setPose( float x, float y, float z ) { _x = x; _y = y; _z = z; }
inline void addPose( float x, float y, float z ) { _x += x; _y += y; _z += z; if( _z < 0.1 ) _z = 0.1; }
void move( float x, float y, float z );
inline void setFov( float horiz_fov, float vert_fov ) { _horiz_fov = horiz_fov; _vert_fov = vert_fov; }
///update vertical fov based on window aspect and current horizontal fov
inline void setAspect( float aspect ) {
//std::cout << "aspect: " << aspect << " vert: " << _vert_fov << " => " << aspect * _vert_fov << std::endl;
//_vert_fov = aspect / _horiz_fov;
_aspect = aspect;
}
inline void setYaw( float yaw ) { _yaw = yaw; }
inline float horizFov( void ) const { return _horiz_fov; }
inline float vertFov( void ) const { return _vert_fov; }
inline void addYaw( float yaw ) { _yaw += yaw; }
inline void setPitch( float pitch ) { _pitch = pitch; }
inline void addPitch( float pitch ) { _pitch += pitch; if( _pitch < 0 ) _pitch = 0; else if( _pitch > 180 ) _pitch = 180; }

inline float realDistance( float z_buf_val ) const {
//formulat found at http://www.cs.unc.edu/~hoff/techrep/openglz.html
//Z = Zn*Zf / (Zf - z*(Zf-Zn))
return _z_near * _z_far / ( _z_far - z_buf_val * ( _z_far - _z_near ) );
}
inline void scroll( float dy ) { _z += dy; }
inline float nearClip( void ) const { return _z_near; }
inline float farClip( void ) const { return _z_far; }
inline void setClip( float near, float far ) { _z_far = far; _z_near = near; }

void Load( Worldfile* wf, int sec );
void Save( Worldfile* wf, int sec );
};

class StgOrthoCamera : public StgCamera
{
private:
float _scale;

float _pixels_width;
float _pixels_height;
float _y_min;
float _y_max;

public:
StgOrthoCamera( void ) : _scale( 15 ) { }
virtual void Draw() const;
virtual void SetProjection( float pixels_width, float pixels_height, float y_min, float y_max );
virtual void SetProjection( void ) const;

void move( float x, float y );
inline void setYaw( float yaw ) { _yaw += yaw; }
inline void setPitch( float pitch ) {
_pitch += pitch;
if( _pitch < -90 )
_pitch = -90;
else if( _pitch > 0 )
_pitch = 0;
}

inline void setScale( float scale ) { _scale = scale; }
inline void setPose( float x, float y) { _x = x; _y = y; }

void scale( float scale, float shift_x = 0, float h = 0, float shift_y = 0, float w = 0 );
inline void resetAngle( void ) { _pitch = _yaw = 0; }

inline float scale() const { return _scale; }

void Load( Worldfile* wf, int sec );
void Save( Worldfile* wf, int sec );
};


class StgCanvas : public Fl_Gl_Window
{
  friend class StgWorldGui; // allow access to private members
  friend class StgModel;
  
private:
  GlColorStack colorstack;
  
  StgCamera* current_camera;
  StgOrthoCamera camera;
  StgPerspectiveCamera perspective_camera;
bool dirty_buffer;

  int startx, starty;
  bool selectedModel;
  bool clicked_empty_space;
int empty_space_startx, empty_space_starty;
  GList* selected_models; ///< a list of models that are currently
  ///selected by the user
  StgModel* last_selection; ///< the most recently selected model
    ///(even if it is now unselected).
    
  stg_msec_t interval; // window refresh interval in ms
  
  GList* ray_list;
  void RecordRay( double x1, double y1, double x2, double y2 );
  void DrawRays();
  void ClearRays();
  void DrawGlobalGrid();
  
  Option
    showBlinken,
    showBlocks,
    showClock,
    showData,
    showFlags,
    showFollow,
    showFootprints,
    showGrid,
    showOccupancy,
    showScreenshots,
showStatus,
    showTrailArrows,
    showTrailRise,
    showTrails,
    showTree,
perspectiveCam,
visualizeAll;
  
public:

StgCanvas( StgWorldGui* world, int x, int y, int W,int H);
~StgCanvas();

bool graphics;
StgWorldGui* world;

  void Screenshot();
  
  void createMenuItems( Fl_Menu_Bar* menu, std::string path );
  
void FixViewport(int W,int H);
void DrawFloor(); //simpler floor compared to grid
void DrawBlocks();
void resetCamera();
virtual void renderFrame();
virtual void draw();
virtual int handle( int event );
void resize(int X,int Y,int W,int H);

void CanvasToWorld( int px, int py,
double *wx, double *wy, double* wz );

StgModel* getModel( int x, int y );
bool selected( StgModel* mod );
void select( StgModel* mod );
void unSelect( StgModel* mod );
void unSelectAll();

inline void setDirtyBuffer( void ) { dirty_buffer = true; }
inline bool dirtyBuffer( void ) const { return dirty_buffer; }

inline void PushColor( stg_color_t col )
{ colorstack.Push( col ); }

void PushColor( double r, double g, double b, double a )
{ colorstack.Push( r,g,b,a ); }

void PopColor(){ colorstack.Pop(); }

void InvertView( uint32_t invertflags );

static void TimerCallback( StgCanvas* canvas );
static void perspectiveCb( Fl_Widget* w, void* p );
  
  void Load( Worldfile* wf, int section );
  void Save( Worldfile* wf, int section );
};


/** Extends StgWorld to implements an FLTK / OpenGL graphical user
interface.
*/
class StgWorldGui : public StgWorld, public Fl_Window
{
  friend class StgCanvas;
  friend class StgModelCamera;

private:
  bool paused; ///< the world only updates when this is false
  //int wf_section;
  StgCanvas* canvas;
  Fl_Menu_Bar* mbar;
  OptionsDlg* oDlg;
  std::vector<Option*> drawOptions;
  void updateOptions();
  stg_usec_t interval_log[INTERVAL_LOG_LEN];
  
  stg_usec_t real_time_of_last_update;
  stg_usec_t interval_real; ///< real-time interval between updates - set this to zero for 'as fast as possible

public:
  static const stg_msec_t DEFAULT_INTERVAL_REAL = 100; ///< real time between updates

  StgWorldGui(int W,int H,const char*L=0);
  ~StgWorldGui();
  
  virtual bool Update();
  
  virtual void Load( const char* filename );
  virtual void UnLoad();
  virtual bool Save( const char* filename );
  
  
  void Start(){ paused = false; };
  void Stop(){ paused = true; };
  void TogglePause(){ paused = !paused; };
  
  /** Get human readable string that describes the current simulation
time. */
std::string ClockString( void );

  /** Set the minimum real time interval between world updates, in
microeconds. */
  void SetRealTimeInterval( stg_usec_t usec )
  { interval_real = usec; }

protected:
virtual void PushColor( stg_color_t col )
{ canvas->PushColor( col ); }

virtual void PushColor( double r, double g, double b, double a )
{ canvas->PushColor( r,g,b,a ); }

virtual void PopColor()
{ canvas->PopColor(); }

void DrawTree( bool leaves );
void DrawFloor();

StgCanvas* GetCanvas( void ) { return canvas; }

private:
// static callback functions
static void windowCb( Fl_Widget* w, void* p );
static void fileLoadCb( Fl_Widget* w, void* p );
static void fileSaveCb( Fl_Widget* w, void* p );
static void fileSaveAsCb( Fl_Widget* w, void* p );
static void fileExitCb( Fl_Widget* w, void* p );
static void viewOptionsCb( Fl_Widget* w, void* p );
static void optionsDlgCb( Fl_Widget* w, void* p );
static void helpAboutCb( Fl_Widget* w, void* p );
  
// GUI functions
bool saveAsDialog();
bool closeWindowQuery();
};


// BLOBFINDER MODEL --------------------------------------------------------

/** blobfinder data packet
*/
typedef struct
{
stg_color_t color;
uint32_t left, top, right, bottom;
stg_meters_t range;
} stg_blobfinder_blob_t;


class StgModelBlobfinder : public StgModel
{
private:

GArray* colors;
GArray* blobs;

// predicate for ray tracing
static bool BlockMatcher( StgBlock* testblock, StgModel* finder );

static Option showBlobData;
public:

unsigned int scan_width;
unsigned int scan_height;
stg_meters_t range;
stg_radians_t fov;
stg_radians_t pan;

  static const char* typestr;

  // constructor
  StgModelBlobfinder( StgWorld* world,
StgModel* parent );
  // destructor
  ~StgModelBlobfinder();
  
  virtual void Startup();
  virtual void Shutdown();
virtual void Update();
virtual void Load();
virtual void DataVisualize();

stg_blobfinder_blob_t* GetBlobs( unsigned int* count )
{
if( count ) *count = blobs->len;
return (stg_blobfinder_blob_t*)blobs->data;
}

/** Start finding blobs with this color.*/
void AddColor( stg_color_t col );

/** Stop tracking blobs with this color */
void RemoveColor( stg_color_t col );

/** Stop tracking all colors. Call this to clear the defaults, then
add colors individually with AddColor(); */
void RemoveAllColors();
};

// ENERGY model --------------------------------------------------------------

/** energy data packet */
typedef struct
{
/** estimate of current energy stored */
stg_joules_t stored;

/** TRUE iff the device is receiving energy from a charger */
stg_bool_t charging;

/** diatance to charging device */
stg_meters_t range;

/** an array of pointers to connected models */
GPtrArray* connections;
} stg_energy_data_t;

/** energy config packet (use this to set or get energy configuration)*/
typedef struct
{
/** maximum storage capacity */
stg_joules_t capacity;

/** When charging another device, supply this many Joules/sec at most*/
stg_watts_t give_rate;

/** When charging from another device, receive this many Joules/sec at most*/
stg_watts_t take_rate;

/** length of the charging probe */
stg_meters_t probe_range;

/** iff TRUE, this device will supply power to connected devices */
stg_bool_t give;

} stg_energy_config_t;

// there is currently no energy command packet


// LASER MODEL --------------------------------------------------------

/** laser sample packet
*/
typedef struct
{
  stg_meters_t range; ///< range to laser hit in meters
  double reflectance; ///< intensity of the reflection 0.0 to 1.0
} stg_laser_sample_t;

typedef struct
{
  uint32_t sample_count;
  uint32_t resolution;
  stg_range_bounds_t range_bounds;
  stg_radians_t fov;
} stg_laser_cfg_t;

class StgModelLaser : public StgModel
{
private:
  int dl_debug_laser;
  
  /** OpenGL displaylist for laser data */
  int data_dl;
  bool data_dirty;

  stg_laser_sample_t* samples;
  uint32_t sample_count;
  stg_meters_t range_min, range_max;
  stg_radians_t fov;
  uint32_t resolution;
  
  static Option showLaserData;
  static Option showLaserStrikes;
  
public:
  static const char* typestr;
  // constructor
  StgModelLaser( StgWorld* world,
StgModel* parent );
  
  // destructor
  ~StgModelLaser();
  
  virtual void Startup();
  virtual void Shutdown();
  virtual void Update();
  virtual void Load();
  virtual void Print( char* prefix );
  virtual void DataVisualize();
  
  uint32_t GetSampleCount(){ return sample_count; }
  
  stg_laser_sample_t* GetSamples( uint32_t* count=NULL);
  
  void SetSamples( stg_laser_sample_t* samples, uint32_t count);
  
  // Get the user-tweakable configuration of the laser
  stg_laser_cfg_t GetConfig( );
  
  // Set the user-tweakable configuration of the laser
  void SetConfig( stg_laser_cfg_t cfg );
};

// \todo GRIPPER MODEL --------------------------------------------------------

// typedef enum {
// STG_GRIPPER_PADDLE_OPEN = 0, // default state
// STG_GRIPPER_PADDLE_CLOSED,
// STG_GRIPPER_PADDLE_OPENING,
// STG_GRIPPER_PADDLE_CLOSING,
// } stg_gripper_paddle_state_t;

// typedef enum {
// STG_GRIPPER_LIFT_DOWN = 0, // default state
// STG_GRIPPER_LIFT_UP,
// STG_GRIPPER_LIFT_UPPING, // verbed these to match the paddle state
// STG_GRIPPER_LIFT_DOWNING,
// } stg_gripper_lift_state_t;

// typedef enum {
// STG_GRIPPER_CMD_NOP = 0, // default state
// STG_GRIPPER_CMD_OPEN,
// STG_GRIPPER_CMD_CLOSE,
// STG_GRIPPER_CMD_UP,
// STG_GRIPPER_CMD_DOWN
// } stg_gripper_cmd_type_t;

// /** gripper configuration packet
// */
// typedef struct
// {
// stg_size_t paddle_size; ///< paddle dimensions

// stg_gripper_paddle_state_t paddles;
// stg_gripper_lift_state_t lift;

// double paddle_position; ///< 0.0 = full open, 1.0 full closed
// double lift_position; ///< 0.0 = full down, 1.0 full up

// stg_meters_t inner_break_beam_inset; ///< distance from the end of the paddle
// stg_meters_t outer_break_beam_inset; ///< distance from the end of the paddle
// stg_bool_t paddles_stalled; // true iff some solid object stopped
// // the paddles closing or opening

// GSList *grip_stack; ///< stack of items gripped
// int grip_stack_size; ///< maximum number of objects in stack, or -1 for unlimited

// double close_limit; ///< How far the gripper can close. If < 1.0, the gripper has its mouth full.

// } stg_gripper_config_t;

// /** gripper command packet
// */
// typedef struct
// {
// stg_gripper_cmd_type_t cmd;
// int arg;
// } stg_gripper_cmd_t;


// /** gripper data packet
// */
// typedef struct
// {
// stg_gripper_paddle_state_t paddles;
// stg_gripper_lift_state_t lift;

// double paddle_position; ///< 0.0 = full open, 1.0 full closed
// double lift_position; ///< 0.0 = full down, 1.0 full up

// stg_bool_t inner_break_beam; ///< non-zero iff beam is broken
// stg_bool_t outer_break_beam; ///< non-zero iff beam is broken

// stg_bool_t paddle_contacts[2]; ///< non-zero iff paddles touch something

// stg_bool_t paddles_stalled; // true iff some solid object stopped
// // the paddles closing or opening

// int stack_count; ///< number of objects in stack


// } stg_gripper_data_t;


// \todo BUMPER MODEL --------------------------------------------------------

// typedef struct
// {
// stg_pose_t pose;
// stg_meters_t length;
// } stg_bumper_config_t;

// typedef struct
// {
// StgModel* hit;
// stg_point_t hit_point;
// } stg_bumper_sample_t;


// FIDUCIAL MODEL --------------------------------------------------------

/** fiducial config packet
*/
typedef struct
{
stg_meters_t max_range_anon; //< maximum detection range
stg_meters_t max_range_id; ///< maximum range at which the ID can be read
stg_meters_t min_range; ///< minimum detection range
stg_radians_t fov; ///< field of view
stg_radians_t heading; ///< center of field of view

/// only detects fiducials with a key string that matches this one
/// (defaults to NULL)
int key;
} stg_fiducial_config_t;

/** fiducial data packet
*/
typedef struct
{
stg_meters_t range; ///< range to the target
stg_radians_t bearing; ///< bearing to the target
stg_pose_t geom; ///< size and relative angle of the target
stg_pose_t pose; ///< Absolute accurate position of the target in world coordinates (it's cheating to use this in robot controllers!)
int id; ///< the identifier of the target, or -1 if none can be detected.

} stg_fiducial_t;

class StgModelFiducial : public StgModel
{
private:
// if neighbor is visible, add him to the fiducial scan
void AddModelIfVisible( StgModel* him );

// static wrapper function can be used as a function pointer
static void AddModelIfVisibleStatic( gpointer key,
StgModel* him,
StgModelFiducial* me )
{ if( him != me ) me->AddModelIfVisible( him ); };

virtual void Update();
virtual void DataVisualize();

GArray* data;

static Option showFiducialData;

public:
  static const char* typestr;
  // constructor
  StgModelFiducial( StgWorld* world,
StgModel* parent );
  // destructor
  virtual ~StgModelFiducial();
  
virtual void Load();

stg_meters_t max_range_anon; //< maximum detection range
stg_meters_t max_range_id; ///< maximum range at which the ID can be read
stg_meters_t min_range; ///< minimum detection range
stg_radians_t fov; ///< field of view
stg_radians_t heading; ///< center of field of view
int key; ///< /// only detect fiducials with a key that matches this one (defaults 0)

stg_fiducial_t* fiducials; ///< array of detected fiducials
uint32_t fiducial_count; ///< the number of fiducials detected
};


// RANGER MODEL --------------------------------------------------------

typedef struct
{
stg_pose_t pose;
stg_size_t size;
stg_bounds_t bounds_range;
stg_radians_t fov;
int ray_count;
} stg_ranger_sensor_t;

class StgModelRanger : public StgModel
{
protected:

virtual void Startup();
virtual void Shutdown();
virtual void Update();
virtual void DataVisualize();

public:
  static const char* typestr;
// constructor
StgModelRanger( StgWorld* world,
StgModel* parent );
// destructor
virtual ~StgModelRanger();

virtual void Load();
virtual void Print( char* prefix );

uint32_t sensor_count;
stg_ranger_sensor_t* sensors;
stg_meters_t* samples;

private:
static Option showRangerData;
static Option showRangerTransducers;

};

// BLINKENLIGHT MODEL ----------------------------------------------------
class StgModelBlinkenlight : public StgModel
{
private:
double dutycycle;
bool enabled;
stg_msec_t period;
bool on;

static Option showBlinkenData;
public:

  static const char* typestr;
StgModelBlinkenlight( StgWorld* world,
StgModel* parent );

~StgModelBlinkenlight();

virtual void Load();
virtual void Update();
virtual void DataVisualize();
};

// CAMERA MODEL ----------------------------------------------------
typedef struct {
// GL_V3F
GLfloat x, y, z;
} ColoredVertex;

class StgModelCamera : public StgModel
{
private:
StgCanvas* _canvas;

GLfloat* _frame_data; //opengl read buffer
GLubyte* _frame_color_data; //opengl read buffer

bool _valid_vertexbuf_cache;
ColoredVertex* _vertexbuf_cache; //cached unit vectors with appropriate rotations (these must be scalled by z-buffer length)

int _width; //width of buffer
int _height; //height of buffer
static const int _depth = 4;

int _camera_quads_size;
GLfloat* _camera_quads;
GLubyte* _camera_colors;

static Option showCameraData;

StgPerspectiveCamera _camera;
float _yaw_offset; //position camera is mounted at
float _pitch_offset;

///Take a screenshot from the camera's perspective. return: true for sucess, and data is available via FrameDepth() / FrameColor()
bool GetFrame();

public:
StgModelCamera( StgWorld* world,
StgModel* parent );

~StgModelCamera();

virtual void Load();

///Capture a new frame ( calls GetFrame )
virtual void Update();

///Draw Camera Model - TODO
//virtual void Draw( uint32_t flags, StgCanvas* canvas );

///Draw camera visualization
virtual void DataVisualize();

///width of captured image
inline int getWidth( void ) const { return _width; }

///height of captured image
inline int getHeight( void ) const { return _height; }

///get reference to camera used
inline const StgPerspectiveCamera& getCamera( void ) const { return _camera; }

///get a reference to camera depth buffer
inline const GLfloat* FrameDepth() const { return _frame_data; }

///get a reference to camera color image. 3 bytes (RGB) per pixel
inline const GLubyte* FrameColor() const { return _frame_color_data; }

///change the pitch
inline void setPitch( float pitch ) { _pitch_offset = pitch; _valid_vertexbuf_cache = false; }

///change the yaw
inline void setYaw( float yaw ) { _yaw_offset = yaw; _valid_vertexbuf_cache = false; }
};

// POSITION MODEL --------------------------------------------------------

/** Define a position control method */
typedef enum
{ STG_POSITION_CONTROL_VELOCITY,
STG_POSITION_CONTROL_POSITION
} stg_position_control_mode_t;

/** Define a localization method */
typedef enum
{ STG_POSITION_LOCALIZATION_GPS,
STG_POSITION_LOCALIZATION_ODOM
} stg_position_localization_mode_t;

/** Define a driving method */
typedef enum
{ STG_POSITION_DRIVE_DIFFERENTIAL,
STG_POSITION_DRIVE_OMNI,
STG_POSITION_DRIVE_CAR
} stg_position_drive_mode_t;


class StgModelPosition : public StgModel
{
private:
stg_pose_t goal; //< the current velocity or pose to reach, depending on the value of control_mode
stg_position_control_mode_t control_mode;
stg_position_drive_mode_t drive_mode;
stg_position_localization_mode_t localization_mode; ///< global or local mode
stg_velocity_t integration_error; ///< errors to apply in simple odometry model
public:
  static const char* typestr;
// constructor
StgModelPosition( StgWorld* world,
StgModel* parent );
// destructor
~StgModelPosition();

virtual void Startup();
virtual void Shutdown();
virtual void Update();
virtual void Load();

/** Set the current pose estimate.*/
void SetOdom( stg_pose_t odom );

/** Sets the control_mode to STG_POSITION_CONTROL_VELOCITY and sets
the goal velocity. */
void SetSpeed( double x, double y, double a );
void SetXSpeed( double x );
void SetYSpeed( double y );
void SetZSpeed( double z );
void SetTurnSpeed( double a );
void SetSpeed( stg_velocity_t vel );

/** Sets the control mode to STG_POSITION_CONTROL_POSITION and sets
the goal pose */
void GoTo( double x, double y, double a );
void GoTo( stg_pose_t pose );

// localization state
stg_pose_t est_pose; ///< position estimate in local coordinates
stg_pose_t est_pose_error; ///< estimated error in position estimate
stg_pose_t est_origin; ///< global origin of the local coordinate system
};


}; // end namespace stg

/*@}*/

#endif
Something went wrong with that request. Please try again.