This file is indexed.

/usr/include/ros/node_handle.h is in libroscpp-dev 1.11.16-3.

This file is owned by root:root, with mode 0o644.

The actual contents of the file can be viewed below.

   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
/*
 * Copyright (C) 2009, Willow Garage, Inc.
 *
 * Redistribution and use in source and binary forms, with or without
 * modification, are permitted provided that the following conditions are met:
 *   * Redistributions of source code must retain the above copyright notice,
 *     this list of conditions and the following disclaimer.
 *   * Redistributions in binary form must reproduce the above copyright
 *     notice, this list of conditions and the following disclaimer in the
 *     documentation and/or other materials provided with the distribution.
 *   * Neither the names of Stanford University or Willow Garage, Inc. nor the names of its
 *     contributors may be used to endorse or promote products derived from
 *     this software without specific prior written permission.
 *
 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
 * POSSIBILITY OF SUCH DAMAGE.
 */

#ifndef ROSCPP_NODE_HANDLE_H
#define ROSCPP_NODE_HANDLE_H

#include "ros/forwards.h"
#include "ros/publisher.h"
#include "ros/subscriber.h"
#include "ros/service_server.h"
#include "ros/service_client.h"
#include "ros/timer.h"
#include "ros/rate.h"
#include "ros/wall_timer.h"
#include "ros/advertise_options.h"
#include "ros/advertise_service_options.h"
#include "ros/subscribe_options.h"
#include "ros/service_client_options.h"
#include "ros/timer_options.h"
#include "ros/wall_timer_options.h"
#include "ros/spinner.h"
#include "ros/init.h"
#include "common.h"

#include <boost/bind.hpp>

#include <xmlrpcpp/XmlRpcValue.h>

namespace ros
{

  class NodeHandleBackingCollection;

  /**
   * \brief roscpp's interface for creating subscribers, publishers, etc.
   *
   * This class is used for writing nodes.  It provides a RAII interface
   * to this process' node, in that when the first NodeHandle is
   * created, it instantiates everything necessary for this node, and
   * when the last NodeHandle goes out of scope it shuts down the node.
   *
   * NodeHandle uses reference counting internally, and copying a
   * NodeHandle is very lightweight.
   *
   * You must call one of the ros::init functions prior to instantiating
   * this class.
   *
   * The most widely used methods are:
   *   - Setup:
   *    - ros::init()
   *   - Publish / subscribe messaging:
   *    - advertise()
   *    - subscribe()
   *   - RPC services:
   *    - advertiseService()
   *    - serviceClient()
   *    - ros::service::call()
   *   - Parameters:
   *    - getParam()
   *    - setParam()
   */
  class ROSCPP_DECL NodeHandle
  {
  public:
    /**
     * \brief Constructor
     *
     * When a NodeHandle is constructed, it checks to see if the global
     * node state has already been started.  If so, it increments a
     * global reference count.  If not, it starts the node with
     * ros::start() and sets the reference count to 1.
     *
     * \param ns Namespace for this NodeHandle.  This acts in addition to any namespace assigned to this ROS node.
     *           eg. If the node's namespace is "/a" and the namespace passed in here is "b", all 
     *           topics/services/parameters will be prefixed with "/a/b/"
     * \param remappings Remappings for this NodeHandle.
     * \throws InvalidNameException if the namespace is not a valid graph resource name
     */
    NodeHandle(const std::string& ns = std::string(), const M_string& remappings = M_string());
    /**
     * \brief Copy constructor
     *
     * When a NodeHandle is copied, it inherits the namespace of the
     * NodeHandle being copied, and increments the reference count of
     * the global node state by 1.
     */
    NodeHandle(const NodeHandle& rhs);
    /**
     * \brief Parent constructor
     *
     * This version of the constructor takes a "parent" NodeHandle, and is equivalent to:
     \verbatim
     NodeHandle child(parent.getNamespace() + "/" + ns);
     \endverbatim
     *
     * When a NodeHandle is copied, it inherits the namespace of the
     * NodeHandle being copied, and increments the reference count of
     * the global node state by 1.
     *
     * \throws InvalidNameException if the namespace is not a valid
     * graph resource name
     */
    NodeHandle(const NodeHandle& parent, const std::string& ns);
    /**
     * \brief Parent constructor
     *
     * This version of the constructor takes a "parent" NodeHandle, and is equivalent to:
     \verbatim
     NodeHandle child(parent.getNamespace() + "/" + ns, remappings);
     \endverbatim
     *
     * This version also lets you pass in name remappings that are specific to this NodeHandle
     *
     * When a NodeHandle is copied, it inherits the namespace of the NodeHandle being copied, 
     * and increments the reference count of the global node state
     * by 1.
     * \throws InvalidNameException if the namespace is not a valid graph resource name
     */
    NodeHandle(const NodeHandle& parent, const std::string& ns, const M_string& remappings);
    /**
     * \brief Destructor
     *
     * When a NodeHandle is destroyed, it decrements a global reference
     * count by 1, and if the reference count is now 0, shuts down the
     * node.
     */
    ~NodeHandle();

    NodeHandle& operator=(const NodeHandle& rhs);

    /**
     * \brief Set the default callback queue to be used by this NodeHandle.
     *
     * Setting this will cause any callbacks from
     * advertisements/subscriptions/services/etc. to happen through the
     * use of the specified queue.  NULL (the default) causes the global
     * queue (serviced by ros::spin() and ros::spinOnce()) to be used.
     */
    void setCallbackQueue(CallbackQueueInterface* queue);

    /**
     * \brief Returns the callback queue associated with this
     * NodeHandle.  If none has been explicitly set, returns the global
     * queue.
     */
    CallbackQueueInterface* getCallbackQueue() const 
    { 
      return callback_queue_ ? callback_queue_ : (CallbackQueueInterface*)getGlobalCallbackQueue(); 
    }

    /**
     * \brief Returns the namespace associated with this NodeHandle
     */
    const std::string& getNamespace() const { return namespace_; }

    /**
     * \brief Returns the namespace associated with this NodeHandle as
     * it was passed in (before it was resolved)
     */
    const std::string& getUnresolvedNamespace() const { return unresolved_namespace_; }

    /** \brief Resolves a name into a fully-qualified name
     *
     * Resolves a name into a fully qualified name, eg. "blah" =>
     * "/namespace/blah". By default also applies any matching
     * name-remapping rules (which were usually supplied on the command
     * line at startup) to the given name, returning the resulting
     * remapped name.
     *
     * \param name Name to remap
     *
     * \param remap Whether to apply name-remapping rules
     *
     * \return Resolved name.
     *
     * \throws InvalidNameException If the name begins with a tilde, or is an otherwise invalid graph resource name
     */
    std::string resolveName(const std::string& name, bool remap = true) const;

    //////////////////////////////////////////////////////////////////////////////////////////////////////////////
    // Versions of advertise()
    //////////////////////////////////////////////////////////////////////////////////////////////////////////////
    /**
     * \brief Advertise a topic, simple version
     *
     * This call connects to the master to publicize that the node will be
     * publishing messages on the given topic.  This method returns a Publisher that allows you to
     * publish a message on this topic.
     *
     * This version of advertise is a templated convenience function, and can be used like so
     *
     *   ros::Publisher pub = handle.advertise<std_msgs::Empty>("my_topic", 1);
     *
     * \param topic Topic to advertise on
     *
     * \param queue_size Maximum number of outgoing messages to be
     * queued for delivery to subscribers
     *
     * \param latch (optional) If true, the last message published on
     * this topic will be saved and sent to new subscribers when they
     * connect
     *
     * \return On success, a Publisher that, when it goes out of scope,
     * will automatically release a reference on this advertisement.  On
     * failure, an empty Publisher.
     *
     * \throws InvalidNameException If the topic name begins with a
     * tilde, or is an otherwise invalid graph resource name, or is an
     * otherwise invalid graph resource name
     */
    template <class M>
    Publisher advertise(const std::string& topic, uint32_t queue_size, bool latch = false)
    {
      AdvertiseOptions ops;
      ops.template init<M>(topic, queue_size);
      ops.latch = latch;
      return advertise(ops);
    }

    /**
     * \brief Advertise a topic, with most of the available options, including subscriber status callbacks
     *
     * This call connects to the master to publicize that the node will be
     * publishing messages on the given topic.  This method returns a Publisher that allows you to
     * publish a message on this topic.
     *
     * This version of advertise allows you to pass functions to be called when new subscribers connect and
     * disconnect.  With bare functions it can be used like so:
     \verbatim
     void connectCallback(const ros::SingleSubscriberPublisher& pub)
     {
     // Do something
     }

     handle.advertise<std_msgs::Empty>("my_topic", 1, (ros::SubscriberStatusCallback)connectCallback);
     \endverbatim
     *
     * With class member functions it can be used with boost::bind:
     \verbatim
     void MyClass::connectCallback(const ros::SingleSubscriberPublisher& pub)
     {
     // Do something
     }

     MyClass my_class;
     ros::Publisher pub = handle.advertise<std_msgs::Empty>("my_topic", 1, 
                                                            boost::bind(&MyClass::connectCallback, my_class, _1));
     \endverbatim
     *
   *
   * \param topic Topic to advertise on
   *
   * \param queue_size Maximum number of outgoing messages to be queued for delivery to subscribers
   *
   * \param connect_cb Function to call when a subscriber connects
   *
   * \param disconnect_cb (optional) Function to call when a subscriber disconnects
     *
   * \param tracked_object (optional) A shared pointer to an object to track for these callbacks.  If set, the a weak_ptr will be created to this object,
   * and if the reference count goes to 0 the subscriber callbacks will not get called.
   * Note that setting this will cause a new reference to be added to the object before the
   * callback, and for it to go out of scope (and potentially be deleted) in the code path (and therefore
   * thread) that the callback is invoked from.
   * \param latch (optional) If true, the last message published on this topic will be saved and sent to new subscribers when they connect
   * \return On success, a Publisher that, when it goes out of scope, will automatically release a reference
   * on this advertisement.  On failure, an empty Publisher which can be checked with:
\verbatim
ros::NodeHandle nodeHandle;
ros::publisher pub = nodeHandle.advertise<std_msgs::Empty>("my_topic", 1, (ros::SubscriberStatusCallback)callback);
if (pub)  // Enter if publisher is valid
{
...
}
\endverbatim
   * \throws InvalidNameException If the topic name begins with a tilde, or is an otherwise invalid graph resource name
   */
  template <class M>
  Publisher advertise(const std::string& topic, uint32_t queue_size,
                            const SubscriberStatusCallback& connect_cb,
                            const SubscriberStatusCallback& disconnect_cb = SubscriberStatusCallback(),
                            const VoidConstPtr& tracked_object = VoidConstPtr(),
                            bool latch = false)
  {
    AdvertiseOptions ops;
    ops.template init<M>(topic, queue_size, connect_cb, disconnect_cb);
    ops.tracked_object = tracked_object;
    ops.latch = latch;
    return advertise(ops);
  }

  /**
   * \brief Advertise a topic, with full range of AdvertiseOptions
   *
   * This call connects to the master to publicize that the node will be
   * publishing messages on the given topic.  This method returns a Publisher that allows you to
   * publish a message on this topic.
   *
   * This is an advanced version advertise() that exposes all options (through the AdvertiseOptions structure)
   *
   * \param ops Advertise options to use
   * \return On success, a Publisher that, when it goes out of scope, will automatically release a reference
   * on this advertisement.  On failure, an empty Publisher which can be checked with:
\verbatim
ros::NodeHandle nodeHandle;
ros::AdvertiseOptions ops;
...
ros::publisher pub = nodeHandle.advertise(ops);
if (pub)  // Enter if publisher is valid
{
...
}
\endverbatim
   *
   * \throws InvalidNameException If the topic name begins with a tilde, or is an otherwise invalid graph resource name
   */
  Publisher advertise(AdvertiseOptions& ops);


  //////////////////////////////////////////////////////////////////////////////////////////////////////////////
  // Versions of subscribe()
  //////////////////////////////////////////////////////////////////////////////////////////////////////////////
  /**
   * \brief Subscribe to a topic, version for class member function with bare pointer
   *
   * This method connects to the master to register interest in a given
   * topic.  The node will automatically be connected with publishers on
   * this topic.  On each message receipt, fp is invoked and passed a shared pointer
   * to the message received.  This message should \b not be changed in place, as it
   * is shared with any other subscriptions to this topic.
   *
   * This version of subscribe is a convenience function for using member functions, and can be used like so:
\verbatim
void Foo::callback(const std_msgs::Empty::ConstPtr& message)
{
}

Foo foo_object;
ros::Subscriber sub = handle.subscribe("my_topic", 1, &Foo::callback, &foo_object);
\endverbatim
   *
   * \param M [template] M here is the callback parameter type (e.g. const boost::shared_ptr<M const>& or const M&), \b not the message type, and should almost always be deduced
   * \param topic Topic to subscribe to
   * \param queue_size Number of incoming messages to queue up for
   * processing (messages in excess of this queue capacity will be
   * discarded).
   * \param fp Member function pointer to call when a message has arrived
   * \param obj Object to call fp on
   * \param transport_hints a TransportHints structure which defines various transport-related options
   * \return On success, a Subscriber that, when all copies of it go out of scope, will unsubscribe from this topic.
   * On failure, an empty Subscriber which can be checked with:
\verbatim
ros::NodeHandle nodeHandle;
void Foo::callback(const std_msgs::Empty::ConstPtr& message) {}
boost::shared_ptr<Foo> foo_object(new Foo);
ros::Subscriber sub = nodeHandle.subscribe("my_topic", 1, &Foo::callback, foo_object);
if (sub)  // Enter if subscriber is valid
{
...
}
\endverbatim
   *  \throws InvalidNameException If the topic name begins with a tilde, or is an otherwise invalid graph resource name
   *  \throws ConflictingSubscriptionException If this node is already subscribed to the same topic with a different datatype
   */
  template<class M, class T>
  Subscriber subscribe(const std::string& topic, uint32_t queue_size, void(T::*fp)(M), T* obj, 
                       const TransportHints& transport_hints = TransportHints())
  {
    SubscribeOptions ops;
    ops.template initByFullCallbackType<M>(topic, queue_size, boost::bind(fp, obj, _1));
    ops.transport_hints = transport_hints;
    return subscribe(ops);
  }

  /// and the const version
  template<class M, class T>
  Subscriber subscribe(const std::string& topic, uint32_t queue_size, void(T::*fp)(M) const, T* obj, 
                       const TransportHints& transport_hints = TransportHints())
  {
    SubscribeOptions ops;
    ops.template initByFullCallbackType<M>(topic, queue_size, boost::bind(fp, obj, _1));
    ops.transport_hints = transport_hints;
    return subscribe(ops);
  }

  /**
   * \brief Subscribe to a topic, version for class member function with bare pointer
   *
   * This method connects to the master to register interest in a given
   * topic.  The node will automatically be connected with publishers on
   * this topic.  On each message receipt, fp is invoked and passed a shared pointer
   * to the message received.  This message should \b not be changed in place, as it
   * is shared with any other subscriptions to this topic.
   *
   * This version of subscribe is a convenience function for using member functions, and can be used like so:
\verbatim
void Foo::callback(const std_msgs::Empty::ConstPtr& message)
{
}

Foo foo_object;
ros::Subscriber sub = handle.subscribe("my_topic", 1, &Foo::callback, &foo_object);
\endverbatim
   *
   * \param M [template] M here is the message type
   * \param topic Topic to subscribe to
   * \param queue_size Number of incoming messages to queue up for
   * processing (messages in excess of this queue capacity will be
   * discarded).
   * \param fp Member function pointer to call when a message has arrived
   * \param obj Object to call fp on
   * \param transport_hints a TransportHints structure which defines various transport-related options
   * \return On success, a Subscriber that, when all copies of it go out of scope, will unsubscribe from this topic.
   * On failure, an empty Subscriber which can be checked with:
\verbatim
ros::NodeHandle nodeHandle;
void Foo::callback(const std_msgs::Empty::ConstPtr& message) {}
boost::shared_ptr<Foo> foo_object(new Foo);
ros::Subscriber sub = nodeHandle.subscribe("my_topic", 1, &Foo::callback, foo_object);
if (sub)  // Enter if subscriber is valid
{
...
}
\endverbatim
   *  \throws InvalidNameException If the topic name begins with a tilde, or is an otherwise invalid graph resource name
   *  \throws ConflictingSubscriptionException If this node is already subscribed to the same topic with a different datatype
   */
  template<class M, class T>
  Subscriber subscribe(const std::string& topic, uint32_t queue_size, 
                       void(T::*fp)(const boost::shared_ptr<M const>&), T* obj, 
                       const TransportHints& transport_hints = TransportHints())
  {
    SubscribeOptions ops;
    ops.template init<M>(topic, queue_size, boost::bind(fp, obj, _1));
    ops.transport_hints = transport_hints;
    return subscribe(ops);
  }
  template<class M, class T>
  Subscriber subscribe(const std::string& topic, uint32_t queue_size, 
                       void(T::*fp)(const boost::shared_ptr<M const>&) const, T* obj, 
                       const TransportHints& transport_hints = TransportHints())
  {
    SubscribeOptions ops;
    ops.template init<M>(topic, queue_size, boost::bind(fp, obj, _1));
    ops.transport_hints = transport_hints;
    return subscribe(ops);
  }

  /**
   * \brief Subscribe to a topic, version for class member function with shared_ptr
   *
   * This method connects to the master to register interest in a given
   * topic.  The node will automatically be connected with publishers on
   * this topic.  On each message receipt, fp is invoked and passed a shared pointer
   * to the message received.  This message should \b not be changed in place, as it
   * is shared with any other subscriptions to this topic.
   *
   * This version of subscribe is a convenience function for using member functions on a shared_ptr:
\verbatim
void Foo::callback(const std_msgs::Empty::ConstPtr& message)
{
}

boost::shared_ptr<Foo> foo_object(new Foo);
ros::Subscriber sub = handle.subscribe("my_topic", 1, &Foo::callback, foo_object);
\endverbatim
   *
   * \param M [template] M here is the callback parameter type (e.g. const boost::shared_ptr<M const>& or const M&), \b not the message type, and should almost always be deduced
   * \param topic Topic to subscribe to
   * \param queue_size Number of incoming messages to queue up for
   * processing (messages in excess of this queue capacity will be
   * discarded).
   * \param fp Member function pointer to call when a message has arrived
   * \param obj Object to call fp on.  Since this is a shared pointer, the object will automatically be tracked with a weak_ptr
   * so that if it is deleted before the Subscriber goes out of scope the callback will no longer be called (and therefore will not crash).
   * \param transport_hints a TransportHints structure which defines various transport-related options
   * \return On success, a Subscriber that, when all copies of it go out of scope, will unsubscribe from this topic.
   * On failure, an empty Subscriber which can be checked with:
\verbatim
ros::NodeHandle nodeHandle;
void Foo::callback(const std_msgs::Empty::ConstPtr& message) {}
boost::shared_ptr<Foo> foo_object(new Foo);
ros::Subscriber sub = nodeHandle.subscribe("my_topic", 1, &Foo::callback, foo_object);
if (sub)  // Enter if subscriber is valid
{
...
}
\endverbatim
   *  \throws InvalidNameException If the topic name begins with a tilde, or is an otherwise invalid graph resource name
   *  \throws ConflictingSubscriptionException If this node is already subscribed to the same topic with a different datatype
   */
  template<class M, class T>
  Subscriber subscribe(const std::string& topic, uint32_t queue_size, void(T::*fp)(M), 
                       const boost::shared_ptr<T>& obj, const TransportHints& transport_hints = TransportHints())
  {
    SubscribeOptions ops;
    ops.template initByFullCallbackType<M>(topic, queue_size, boost::bind(fp, obj.get(), _1));
    ops.tracked_object = obj;
    ops.transport_hints = transport_hints;
    return subscribe(ops);
  }

  template<class M, class T>
  Subscriber subscribe(const std::string& topic, uint32_t queue_size, void(T::*fp)(M) const, 
                       const boost::shared_ptr<T>& obj, const TransportHints& transport_hints = TransportHints())
  {
    SubscribeOptions ops;
    ops.template initByFullCallbackType<M>(topic, queue_size, boost::bind(fp, obj.get(), _1));
    ops.tracked_object = obj;
    ops.transport_hints = transport_hints;
    return subscribe(ops);
  }

  /**
   * \brief Subscribe to a topic, version for class member function with shared_ptr
   *
   * This method connects to the master to register interest in a given
   * topic.  The node will automatically be connected with publishers on
   * this topic.  On each message receipt, fp is invoked and passed a shared pointer
   * to the message received.  This message should \b not be changed in place, as it
   * is shared with any other subscriptions to this topic.
   *
   * This version of subscribe is a convenience function for using member functions on a shared_ptr:
\verbatim
void Foo::callback(const std_msgs::Empty::ConstPtr& message)
{
}

boost::shared_ptr<Foo> foo_object(new Foo);
ros::Subscriber sub = handle.subscribe("my_topic", 1, &Foo::callback, foo_object);
\endverbatim
   *
   * \param M [template] M here is the message type
   * \param topic Topic to subscribe to
   * \param queue_size Number of incoming messages to queue up for
   * processing (messages in excess of this queue capacity will be
   * discarded).
   * \param fp Member function pointer to call when a message has arrived
   * \param obj Object to call fp on.  Since this is a shared pointer, the object will automatically be tracked with a weak_ptr
   * so that if it is deleted before the Subscriber goes out of scope the callback will no longer be called (and therefore will not crash).
   * \param transport_hints a TransportHints structure which defines various transport-related options
   * \return On success, a Subscriber that, when all copies of it go out of scope, will unsubscribe from this topic.
   * On failure, an empty Subscriber which can be checked with:
\verbatim
ros::NodeHandle nodeHandle;
void Foo::callback(const std_msgs::Empty::ConstPtr& message) {}
boost::shared_ptr<Foo> foo_object(new Foo);
ros::Subscriber sub = nodeHandle.subscribe("my_topic", 1, &Foo::callback, foo_object);
if (sub)  // Enter if subscriber is valid
{
...
}
\endverbatim
   *  \throws InvalidNameException If the topic name begins with a tilde, or is an otherwise invalid graph resource name
   *  \throws ConflictingSubscriptionException If this node is already subscribed to the same topic with a different datatype
   */
  template<class M, class T>
  Subscriber subscribe(const std::string& topic, uint32_t queue_size, 
                       void(T::*fp)(const boost::shared_ptr<M const>&), 
                       const boost::shared_ptr<T>& obj, const TransportHints& transport_hints = TransportHints())
  {
    SubscribeOptions ops;
    ops.template init<M>(topic, queue_size, boost::bind(fp, obj.get(), _1));
    ops.tracked_object = obj;
    ops.transport_hints = transport_hints;
    return subscribe(ops);
  }
  template<class M, class T>
  Subscriber subscribe(const std::string& topic, uint32_t queue_size, 
                       void(T::*fp)(const boost::shared_ptr<M const>&) const, 
                       const boost::shared_ptr<T>& obj, const TransportHints& transport_hints = TransportHints())
  {
    SubscribeOptions ops;
    ops.template init<M>(topic, queue_size, boost::bind(fp, obj.get(), _1));
    ops.tracked_object = obj;
    ops.transport_hints = transport_hints;
    return subscribe(ops);
  }

  /**
   * \brief Subscribe to a topic, version for bare function
   *
   * This method connects to the master to register interest in a given
   * topic.  The node will automatically be connected with publishers on
   * this topic.  On each message receipt, fp is invoked and passed a shared pointer
   * to the message received.  This message should \b not be changed in place, as it
   * is shared with any other subscriptions to this topic.
   *
   * This version of subscribe is a convenience function for using bare functions, and can be used like so:
\verbatim
void callback(const std_msgs::Empty::ConstPtr& message)
{
}

ros::Subscriber sub = handle.subscribe("my_topic", 1, callback);
\endverbatim
   *
   * \param M [template] M here is the callback parameter type (e.g. const boost::shared_ptr<M const>& or const M&), \b not the message type, and should almost always be deduced
   * \param topic Topic to subscribe to
   * \param queue_size Number of incoming messages to queue up for
   * processing (messages in excess of this queue capacity will be
   * discarded).
   * \param fp Function pointer to call when a message has arrived
   * \param transport_hints a TransportHints structure which defines various transport-related options
   * \return On success, a Subscriber that, when all copies of it go out of scope, will unsubscribe from this topic.
   * On failure, an empty Subscriber which can be checked with:
\verbatim
void callback(const std_msgs::Empty::ConstPtr& message){...}
ros::NodeHandle nodeHandle;
ros::Subscriber sub = nodeHandle.subscribe("my_topic", 1, callback);
if (sub)  // Enter if subscriber is valid
{
...
}
\endverbatim
   *  \throws InvalidNameException If the topic name begins with a tilde, or is an otherwise invalid graph resource name
   *  \throws ConflictingSubscriptionException If this node is already subscribed to the same topic with a different datatype
   */
  template<class M>
  Subscriber subscribe(const std::string& topic, uint32_t queue_size, void(*fp)(M), const TransportHints& transport_hints = TransportHints())
  {
    SubscribeOptions ops;
    ops.template initByFullCallbackType<M>(topic, queue_size, fp);
    ops.transport_hints = transport_hints;
    return subscribe(ops);
  }

  /**
   * \brief Subscribe to a topic, version for bare function
   *
   * This method connects to the master to register interest in a given
   * topic.  The node will automatically be connected with publishers on
   * this topic.  On each message receipt, fp is invoked and passed a shared pointer
   * to the message received.  This message should \b not be changed in place, as it
   * is shared with any other subscriptions to this topic.
   *
   * This version of subscribe is a convenience function for using bare functions, and can be used like so:
\verbatim
void callback(const std_msgs::Empty::ConstPtr& message)
{
}

ros::Subscriber sub = handle.subscribe("my_topic", 1, callback);
\endverbatim
   *
   * \param M [template] M here is the message type
   * \param topic Topic to subscribe to
   * \param queue_size Number of incoming messages to queue up for
   * processing (messages in excess of this queue capacity will be
   * discarded).
   * \param fp Function pointer to call when a message has arrived
   * \param transport_hints a TransportHints structure which defines various transport-related options
   * \return On success, a Subscriber that, when all copies of it go out of scope, will unsubscribe from this topic.
   * On failure, an empty Subscriber which can be checked with:
\verbatim
void callback(const std_msgs::Empty::ConstPtr& message){...}
ros::NodeHandle nodeHandle;
ros::Subscriber sub = nodeHandle.subscribe("my_topic", 1, callback);
if (sub)  // Enter if subscriber is valid
{
...
}
\endverbatim
   *  \throws InvalidNameException If the topic name begins with a tilde, or is an otherwise invalid graph resource name
   *  \throws ConflictingSubscriptionException If this node is already subscribed to the same topic with a different datatype
   */
  template<class M>
  Subscriber subscribe(const std::string& topic, uint32_t queue_size, void(*fp)(const boost::shared_ptr<M const>&), const TransportHints& transport_hints = TransportHints())
  {
    SubscribeOptions ops;
    ops.template init<M>(topic, queue_size, fp);
    ops.transport_hints = transport_hints;
    return subscribe(ops);
  }

  /**
   * \brief Subscribe to a topic, version for arbitrary boost::function object
   *
   * This method connects to the master to register interest in a given
   * topic.  The node will automatically be connected with publishers on
   * this topic.  On each message receipt, callback is invoked and passed a shared pointer
   * to the message received.  This message should \b not be changed in place, as it
   * is shared with any other subscriptions to this topic.
   *
   * This version of subscribe allows anything bindable to a boost::function object
   *
   * \param M [template] M here is the message type
   * \param topic Topic to subscribe to
   * \param queue_size Number of incoming messages to queue up for
   * processing (messages in excess of this queue capacity will be
   * discarded).
   * \param callback Callback to call when a message has arrived
   * \param tracked_object A shared pointer to an object to track for these callbacks.  If set, the a weak_ptr will be created to this object,
   * and if the reference count goes to 0 the subscriber callbacks will not get called.
   * Note that setting this will cause a new reference to be added to the object before the
   * callback, and for it to go out of scope (and potentially be deleted) in the code path (and therefore
   * thread) that the callback is invoked from.
   * \param transport_hints a TransportHints structure which defines various transport-related options
   * \return On success, a Subscriber that, when all copies of it go out of scope, will unsubscribe from this topic.
   * On failure, an empty Subscriber which can be checked with:
\verbatim
void callback(const std_msgs::Empty::ConstPtr& message){...}
ros::NodeHandle nodeHandle;
ros::Subscriber sub = nodeHandle.subscribe("my_topic", 1, callback);
if (sub)  // Enter if subscriber is valid
{
...
}
\endverbatim
   *  \throws InvalidNameException If the topic name begins with a tilde, or is an otherwise invalid graph resource name
   *  \throws ConflictingSubscriptionException If this node is already subscribed to the same topic with a different datatype
   */
  template<class M>
  Subscriber subscribe(const std::string& topic, uint32_t queue_size, const boost::function<void (const boost::shared_ptr<M const>&)>& callback,
                             const VoidConstPtr& tracked_object = VoidConstPtr(), const TransportHints& transport_hints = TransportHints())
  {
    SubscribeOptions ops;
    ops.template init<M>(topic, queue_size, callback);
    ops.tracked_object = tracked_object;
    ops.transport_hints = transport_hints;
    return subscribe(ops);
  }

  /**
   * \brief Subscribe to a topic, version for arbitrary boost::function object
   *
   * This method connects to the master to register interest in a given
   * topic.  The node will automatically be connected with publishers on
   * this topic.  On each message receipt, callback is invoked and passed a shared pointer
   * to the message received.  This message should \b not be changed in place, as it
   * is shared with any other subscriptions to this topic.
   *
   * This version of subscribe allows anything bindable to a boost::function object
   *
   * \param M [template] the message type
   * \param C [template] the callback parameter type (e.g. const boost::shared_ptr<M const>& or const M&)
   * \param topic Topic to subscribe to
   * \param queue_size Number of incoming messages to queue up for
   * processing (messages in excess of this queue capacity will be
   * discarded).
   * \param callback Callback to call when a message has arrived
   * \param tracked_object A shared pointer to an object to track for these callbacks.  If set, the a weak_ptr will be created to this object,
   * and if the reference count goes to 0 the subscriber callbacks will not get called.
   * Note that setting this will cause a new reference to be added to the object before the
   * callback, and for it to go out of scope (and potentially be deleted) in the code path (and therefore
   * thread) that the callback is invoked from.
   * \param transport_hints a TransportHints structure which defines various transport-related options
   * \return On success, a Subscriber that, when all copies of it go out of scope, will unsubscribe from this topic.
   * On failure, an empty Subscriber which can be checked with:
\verbatim
void callback(const std_msgs::Empty::ConstPtr& message){...}
ros::NodeHandle nodeHandle;
ros::Subscriber sub = nodeHandle.subscribe("my_topic", 1, callback);
if (sub)  // Enter if subscriber is valid
{
...
}
\endverbatim
   *  \throws InvalidNameException If the topic name begins with a tilde, or is an otherwise invalid graph resource name
   *  \throws ConflictingSubscriptionException If this node is already subscribed to the same topic with a different datatype
   */
  template<class M, class C>
  Subscriber subscribe(const std::string& topic, uint32_t queue_size, const boost::function<void (C)>& callback,
                             const VoidConstPtr& tracked_object = VoidConstPtr(), const TransportHints& transport_hints = TransportHints())
  {
    SubscribeOptions ops;
    ops.template initByFullCallbackType<C>(topic, queue_size, callback);
    ops.tracked_object = tracked_object;
    ops.transport_hints = transport_hints;
    return subscribe(ops);
  }

  /**
   * \brief Subscribe to a topic, version with full range of SubscribeOptions
   *
   * This method connects to the master to register interest in a given
   * topic.  The node will automatically be connected with publishers on
   * this topic.  On each message receipt, fp is invoked and passed a shared pointer
   * to the message received.  This message should \b not be changed in place, as it
   * is shared with any other subscriptions to this topic.
   *
   * This version of subscribe allows the full range of options, exposed through the SubscribeOptions class
   *
   * \param ops Subscribe options
   * \return On success, a Subscriber that, when all copies of it go out of scope, will unsubscribe from this topic.
   * On failure, an empty Subscriber which can be checked with:
\verbatim
SubscribeOptions ops;
...
ros::NodeHandle nodeHandle;
ros::Subscriber sub = nodeHandle.subscribe(ops);
if (sub)  // Enter if subscriber is valid
{
...
}
\endverbatim
   *  \throws InvalidNameException If the topic name begins with a tilde, or is an otherwise invalid graph resource name
   *  \throws ConflictingSubscriptionException If this node is already subscribed to the same topic with a different datatype
   */
  Subscriber subscribe(SubscribeOptions& ops);

  //////////////////////////////////////////////////////////////////////////////////////////////////////////////
  // Versions of advertiseService()
  //////////////////////////////////////////////////////////////////////////////////////////////////////////////
  /**
   * \brief Advertise a service, version for class member function with bare pointer
   *
   * This call connects to the master to publicize that the node will be
   * offering an RPC service with the given name.
   *
   * This is a convenience function for using member functions, and can be used like so:
\verbatim
bool Foo::callback(std_srvs::Empty& request, std_srvs::Empty& response)
{
  return true;
}

Foo foo_object;
ros::ServiceServer service = handle.advertiseService("my_service", &Foo::callback, &foo_object);
\endverbatim
   *
   * \param service Service name to advertise on
   * \param srv_func Member function pointer to call when a message has arrived
   * \param obj Object to call srv_func on
   * \return On success, a ServiceServer that, when all copies of it go out of scope, will unadvertise this service.
   * On failure, an empty ServiceServer which can be checked with:
\verbatim
bool Foo::callback(std_srvs::Empty& request, std_srvs::Empty& response)
{
  return true;
}
ros::NodeHandle nodeHandle;
Foo foo_object;
ros::ServiceServer service = nodeHandle.advertiseService("my_service", &Foo::callback, &foo_object);
if (service)  // Enter if advertised service is valid
{
...
}
\endverbatim
   *  \throws InvalidNameException If the service name begins with a tilde, or is an otherwise invalid graph resource name, or is an otherwise invalid graph resource name
   */
  template<class T, class MReq, class MRes>
  ServiceServer advertiseService(const std::string& service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
  {
    AdvertiseServiceOptions ops;
    ops.template init<MReq, MRes>(service, boost::bind(srv_func, obj, _1, _2));
    return advertiseService(ops);
  }

  /**
   * \brief Advertise a service, version for class member function with bare pointer using ros::ServiceEvent as the callback parameter type
   *
   * This call connects to the master to publicize that the node will be
   * offering an RPC service with the given name.
   *
   * This is a convenience function for using member functions, and can be used like so:
\verbatim
bool Foo::callback(ros::ServiceEvent<std_srvs::Empty::Request, std_srvs::Empty::Response>& event)
{
  return true;
}

Foo foo_object;
ros::ServiceServer service = handle.advertiseService("my_service", &Foo::callback, &foo_object);
\endverbatim
   *
   * \param service Service name to advertise on
   * \param srv_func Member function pointer to call when a message has arrived
   * \param obj Object to call srv_func on
   * \return On success, a ServiceServer that, when all copies of it go out of scope, will unadvertise this service.
   * On failure, an empty ServiceServer which can be checked with:
\verbatim
bool Foo::callback(std_srvs::Empty& request, std_srvs::Empty& response)
{
  return true;
}
ros::NodeHandle nodeHandle;
Foo foo_object;
ros::ServiceServer service = nodeHandle.advertiseService("my_service", &Foo::callback, &foo_object);
if (service)  // Enter if advertised service is valid
{
...
}
\endverbatim
   *  \throws InvalidNameException If the service name begins with a tilde, or is an otherwise invalid graph resource name, or is an otherwise invalid graph resource name
   */
  template<class T, class MReq, class MRes>
  ServiceServer advertiseService(const std::string& service, bool(T::*srv_func)(ServiceEvent<MReq, MRes>&), T *obj)
  {
    AdvertiseServiceOptions ops;
    ops.template initBySpecType<ServiceEvent<MReq, MRes> >(service, boost::bind(srv_func, obj, _1));
    return advertiseService(ops);
  }

  /**
   * \brief Advertise a service, version for class member function with shared_ptr
   *
   * This call connects to the master to publicize that the node will be
   * offering an RPC service with the given name.
   *
   * This is a convenience function for using member functions on shared pointers, and can be used like so:
\verbatim
bool Foo::callback(std_srvs::Empty& request, std_srvs::Empty& response)
{
  return true;
}

boost::shared_ptr<Foo> foo_object(new Foo);
ros::ServiceServer service = handle.advertiseService("my_service", &Foo::callback, foo_object);
\endverbatim
   *
   * \param service Service name to advertise on
   * \param srv_func Member function pointer to call when a message has arrived
   * \param obj Object to call srv_func on.  Since this is a shared_ptr, it will automatically be tracked with a weak_ptr,
   * and if the object is deleted the service callback will stop being called (and therefore will not crash).
   * \return On success, a ServiceServer that, when all copies of it go out of scope, will unadvertise this service.
   * On failure, an empty ServiceServer which can be checked with:
\verbatim
bool Foo::callback(std_srvs::Empty& request, std_srvs::Empty& response)
{
  return true;
}
ros::NodeHandle nodeHandle;
Foo foo_object;
ros::ServiceServer service = nodeHandle.advertiseService("my_service", &Foo::callback, &foo_object);
if (service)  // Enter if advertised service is valid
{
...
}
\endverbatim
   * \throws InvalidNameException If the service name begins with a tilde, or is an otherwise invalid graph resource name
   */
  template<class T, class MReq, class MRes>
  ServiceServer advertiseService(const std::string& service, bool(T::*srv_func)(MReq &, MRes &), const boost::shared_ptr<T>& obj)
  {
    AdvertiseServiceOptions ops;
    ops.template init<MReq, MRes>(service, boost::bind(srv_func, obj.get(), _1, _2));
    ops.tracked_object = obj;
    return advertiseService(ops);
  }

  /**
   * \brief Advertise a service, version for class member function with shared_ptr using ros::ServiceEvent as the callback parameter type
   *
   * This call connects to the master to publicize that the node will be
   * offering an RPC service with the given name.
   *
   * This is a convenience function for using member functions on shared pointers, and can be used like so:
\verbatim
bool Foo::callback(ros::ServiceEvent<std_srvs::Empty, std_srvs::Empty>& event)
{
  return true;
}

boost::shared_ptr<Foo> foo_object(new Foo);
ros::ServiceServer service = handle.advertiseService("my_service", &Foo::callback, foo_object);
\endverbatim
   *
   * \param service Service name to advertise on
   * \param srv_func Member function pointer to call when a message has arrived
   * \param obj Object to call srv_func on.  Since this is a shared_ptr, it will automatically be tracked with a weak_ptr,
   * and if the object is deleted the service callback will stop being called (and therefore will not crash).
   * \return On success, a ServiceServer that, when all copies of it go out of scope, will unadvertise this service.
   * On failure, an empty ServiceServer which can be checked with:
\verbatim
bool Foo::callback(std_srvs::Empty& request, std_srvs::Empty& response)
{
  return true;
}
ros::NodeHandle nodeHandle;
Foo foo_object;
ros::ServiceServer service = nodeHandle.advertiseService("my_service", &Foo::callback, &foo_object);
if (service)  // Enter if advertised service is valid
{
...
}
\endverbatim
   * \throws InvalidNameException If the service name begins with a tilde, or is an otherwise invalid graph resource name
   */
  template<class T, class MReq, class MRes>
  ServiceServer advertiseService(const std::string& service, bool(T::*srv_func)(ServiceEvent<MReq, MRes>&), const boost::shared_ptr<T>& obj)
  {
    AdvertiseServiceOptions ops;
    ops.template initBySpecType<ServiceEvent<MReq, MRes> >(service, boost::bind(srv_func, obj.get(), _1));
    ops.tracked_object = obj;
    return advertiseService(ops);
  }

  /**
   * \brief Advertise a service, version for bare function
   *
   * This call connects to the master to publicize that the node will be
   * offering an RPC service with the given name.
   *
   * This is a convenience function for using bare functions, and can be used like so:
\verbatim
bool callback(std_srvs::Empty& request, std_srvs::Empty& response)
{
  return true;
}

ros::ServiceServer service = handle.advertiseService("my_service", callback);
\endverbatim
   *
   * \param service Service name to advertise on
   * \param srv_func function pointer to call when a message has arrived
   * \return On success, a ServiceServer that, when all copies of it go out of scope, will unadvertise this service.
   * On failure, an empty ServiceServer which can be checked with:
\verbatim
bool Foo::callback(std_srvs::Empty& request, std_srvs::Empty& response)
{
  return true;
}
ros::NodeHandle nodeHandle;
Foo foo_object;
ros::ServiceServer service = nodeHandle.advertiseService("my_service", callback);
if (service)  // Enter if advertised service is valid
{
...
}
\endverbatim
   * \throws InvalidNameException If the service name begins with a tilde, or is an otherwise invalid graph resource name
   */
  template<class MReq, class MRes>
  ServiceServer advertiseService(const std::string& service, bool(*srv_func)(MReq&, MRes&))
  {
    AdvertiseServiceOptions ops;
    ops.template init<MReq, MRes>(service, srv_func);
    return advertiseService(ops);
  }

  /**
   * \brief Advertise a service, version for bare function using ros::ServiceEvent as the callback parameter type
   *
   * This call connects to the master to publicize that the node will be
   * offering an RPC service with the given name.
   *
   * This is a convenience function for using bare functions, and can be used like so:
\verbatim
bool callback(ros::ServiceEvent<std_srvs::Empty, std_srvs::Empty>& event)
{
  return true;
}

ros::ServiceServer service = handle.advertiseService("my_service", callback);
\endverbatim
   *
   * \param service Service name to advertise on
   * \param srv_func function pointer to call when a message has arrived
   * \return On success, a ServiceServer that, when all copies of it go out of scope, will unadvertise this service.
   * On failure, an empty ServiceServer which can be checked with:
\verbatim
bool Foo::callback(std_srvs::Empty& request, std_srvs::Empty& response)
{
  return true;
}
ros::NodeHandle nodeHandle;
Foo foo_object;
ros::ServiceServer service = nodeHandle.advertiseService("my_service", callback);
if (service)  // Enter if advertised service is valid
{
...
}
\endverbatim
   * \throws InvalidNameException If the service name begins with a tilde, or is an otherwise invalid graph resource name
   */
  template<class MReq, class MRes>
  ServiceServer advertiseService(const std::string& service, bool(*srv_func)(ServiceEvent<MReq, MRes>&))
  {
    AdvertiseServiceOptions ops;
    ops.template initBySpecType<ServiceEvent<MReq, MRes> >(service, srv_func);
    return advertiseService(ops);
  }

  /**
   * \brief Advertise a service, version for arbitrary boost::function object
   *
   * This call connects to the master to publicize that the node will be
   * offering an RPC service with the given name.
   *
   * This version of advertiseService allows non-class functions, as well as functor objects and boost::bind (along with anything
   * else boost::function supports).
   *
   * \param service Service name to advertise on
   * \param callback Callback to call when the service is called
   * \param tracked_object A shared pointer to an object to track for these callbacks.  If set, the a weak_ptr will be created to this object,
   * and if the reference count goes to 0 the subscriber callbacks will not get called.
   * Note that setting this will cause a new reference to be added to the object before the
   * callback, and for it to go out of scope (and potentially be deleted) in the code path (and therefore
   * thread) that the callback is invoked from.
   * \return On success, a ServiceServer that, when all copies of it go out of scope, will unadvertise this service.
   * On failure, an empty ServiceServer which can be checked with:
\verbatim
bool Foo::callback(std_srvs::Empty& request, std_srvs::Empty& response)
{
  return true;
}
ros::NodeHandle nodeHandle;
Foo foo_object;
ros::ServiceServer service = nodeHandle.advertiseService("my_service", callback);
if (service)  // Enter if advertised service is valid
{
...
}
\endverbatim
   * \throws InvalidNameException If the service name begins with a tilde, or is an otherwise invalid graph resource name
   */
  template<class MReq, class MRes>
  ServiceServer advertiseService(const std::string& service, const boost::function<bool(MReq&, MRes&)>& callback, 
                                 const VoidConstPtr& tracked_object = VoidConstPtr())
  {
    AdvertiseServiceOptions ops;
    ops.template init<MReq, MRes>(service, callback);
    ops.tracked_object = tracked_object;
    return advertiseService(ops);
  }

  /**
   * \brief Advertise a service, version for arbitrary boost::function object using ros::ServiceEvent as the callback parameter type
   *
   * Note that the template parameter S is the full event type, e.g. ros::ServiceEvent<Req, Res>
   *
   * This call connects to the master to publicize that the node will be
   * offering an RPC service with the given name.
   *
   * This version of advertiseService allows non-class functions, as well as functor objects and boost::bind (along with anything
   * else boost::function supports).
   *
   * \param service Service name to advertise on
   * \param callback Callback to call when the service is called
   * \param tracked_object A shared pointer to an object to track for these callbacks.  If set, the a weak_ptr will be created to this object,
   * and if the reference count goes to 0 the subscriber callbacks will not get called.
   * Note that setting this will cause a new reference to be added to the object before the
   * callback, and for it to go out of scope (and potentially be deleted) in the code path (and therefore
   * thread) that the callback is invoked from.
   * \return On success, a ServiceServer that, when all copies of it go out of scope, will unadvertise this service.
   * On failure, an empty ServiceServer which can be checked with:
\verbatim
bool Foo::callback(std_srvs::Empty& request, std_srvs::Empty& response)
{
  return true;
}
ros::NodeHandle nodeHandle;
Foo foo_object;
ros::ServiceServer service = nodeHandle.advertiseService("my_service", callback);
if (service)  // Enter if advertised service is valid
{
...
}
\endverbatim
   * \throws InvalidNameException If the service name begins with a tilde, or is an otherwise invalid graph resource name
   */
  template<class S>
  ServiceServer advertiseService(const std::string& service, const boost::function<bool(S&)>& callback, 
                                 const VoidConstPtr& tracked_object = VoidConstPtr())
  {
    AdvertiseServiceOptions ops;
    ops.template initBySpecType<S>(service, callback);
    ops.tracked_object = tracked_object;
    return advertiseService(ops);
  }

  /**
   * \brief Advertise a service, with full range of AdvertiseServiceOptions
   *
   * This call connects to the master to publicize that the node will be
   * offering an RPC service with the given name.
   *
   * This version of advertiseService allows the full set of options, exposed through the AdvertiseServiceOptions class
   *
   * \param ops Advertise options
   * \return On success, a ServiceServer that, when all copies of it go out of scope, will unadvertise this service.
   * On failure, an empty ServiceServer which can be checked with:
\verbatim
AdvertiseServiceOptions ops;
...
ros::NodeHandle nodeHandle;
ros::ServiceServer service = nodeHandle.advertiseService(ops);
if (service)  // Enter if advertised service is valid
{
...
}
\endverbatim
   * \throws InvalidNameException If the service name begins with a tilde, or is an otherwise invalid graph resource name
   */
  ServiceServer advertiseService(AdvertiseServiceOptions& ops);

  //////////////////////////////////////////////////////////////////////////////////////////////////////////////
  // Versions of serviceClient()
  //////////////////////////////////////////////////////////////////////////////////////////////////////////////

  /** @brief Create a client for a service, version templated on two message types
   *
   * When the last handle reference of a persistent connection is cleared, the connection will automatically close.
   *
   * @param service_name The name of the service to connect to
   * @param persistent Whether this connection should persist.  Persistent services keep the connection to the remote host active
   *        so that subsequent calls will happen faster.  In general persistent services are discouraged, as they are not as
   *        robust to node failure as non-persistent services.
   * @param header_values Key/value pairs you'd like to send along in the connection handshake
   * \throws InvalidNameException If the service name begins with a tilde, or is an otherwise invalid graph resource name
   */
  template<class MReq, class MRes>
  ServiceClient serviceClient(const std::string& service_name, bool persistent = false, 
                              const M_string& header_values = M_string())
  {
    ServiceClientOptions ops;
    ops.template init<MReq, MRes>(service_name, persistent, header_values);
    return serviceClient(ops);
  }

  /** @brief Create a client for a service, version templated on service type
   *
   * When the last handle reference of a persistent connection is cleared, the connection will automatically close.
   *
   * @param service_name The name of the service to connect to
   * @param persistent Whether this connection should persist.  Persistent services keep the connection to the remote host active
   *        so that subsequent calls will happen faster.  In general persistent services are discouraged, as they are not as
   *        robust to node failure as non-persistent services.
   * @param header_values Key/value pairs you'd like to send along in the connection handshake
   * \throws InvalidNameException If the service name begins with a tilde, or is an otherwise invalid graph resource name
   */
  template<class Service>
  ServiceClient serviceClient(const std::string& service_name, bool persistent = false, 
                              const M_string& header_values = M_string())
  {
    ServiceClientOptions ops;
    ops.template init<Service>(service_name, persistent, header_values);
    return serviceClient(ops);
  }

  /** @brief Create a client for a service, version with full range of ServiceClientOptions
   *
   * When the last handle reference of a persistent connection is cleared, the connection will automatically close.
   *
   * @param ops The options for this service client
   * \throws InvalidNameException If the service name begins with a tilde, or is an otherwise invalid graph resource name
   */
  ServiceClient serviceClient(ServiceClientOptions& ops);

  //////////////////////////////////////////////////////////////////////////////////////////////////////////////
  // Versions of createTimer()
  //////////////////////////////////////////////////////////////////////////////////////////////////////////////
  /**
   * \brief Create a timer which will call a callback at the specified rate.  This variant takes
   * a class member function, and a bare pointer to the object to call the method on.
   *
   * When the Timer (and all copies of it) returned goes out of scope, the timer will automatically
   * be stopped, and the callback will no longer be called.
   *
   * \param r The rate at which to call the callback
   * \param callback The method to call
   * \param obj The object to call the method on
   * \param oneshot If true, this timer will only fire once
   * \param autostart If true (default), return timer that is already started
   */
  template<class Handler, class Obj>
  Timer createTimer(Rate r, Handler h, Obj o, bool oneshot = false, bool autostart = true) const
  {
    return createTimer(r.expectedCycleTime(), h, o, oneshot, autostart);
  }

  /**
   * \brief Create a timer which will call a callback at the specified rate.  This variant takes
   * a class member function, and a bare pointer to the object to call the method on.
   *
   * When the Timer (and all copies of it) returned goes out of scope, the timer will automatically
   * be stopped, and the callback will no longer be called.
   *
   * \param period The period at which to call the callback
   * \param callback The method to call
   * \param obj The object to call the method on
   * \param oneshot If true, this timer will only fire once
   * \param autostart If true (default), return timer that is already started
   */
  template<class T>
  Timer createTimer(Duration period, void(T::*callback)(const TimerEvent&) const, T* obj, 
                    bool oneshot = false, bool autostart = true) const
  {
    return createTimer(period, boost::bind(callback, obj, _1), oneshot, autostart);
  }

  /**
   * \brief Create a timer which will call a callback at the specified rate.  This variant takes
   * a class member function, and a bare pointer to the object to call the method on.
   *
   * When the Timer (and all copies of it) returned goes out of scope, the timer will automatically
   * be stopped, and the callback will no longer be called.
   *
   * \param period The period at which to call the callback
   * \param callback The method to call
   * \param obj The object to call the method on
   * \param oneshot If true, this timer will only fire once
   * \param autostart If true (default), return timer that is already started
   */
  template<class T>
  Timer createTimer(Duration period, void(T::*callback)(const TimerEvent&), T* obj, 
                    bool oneshot = false, bool autostart = true) const
  {
    return createTimer(period, boost::bind(callback, obj, _1), oneshot, autostart);
  }

  /**
   * \brief Create a timer which will call a callback at the specified rate.  This variant takes
   * a class member function, and a shared pointer to the object to call the method on.
   *
   * When the Timer (and all copies of it) returned goes out of scope, the timer will automatically
   * be stopped, and the callback will no longer be called.
   *
   * \param period The period at which to call the callback
   * \param callback The method to call
   * \param obj The object to call the method on.  Since this is a shared pointer, the object will
   * automatically be tracked with a weak_ptr so that if it is deleted before the Timer goes out of
   * scope the callback will no longer be called (and therefore will not crash).
   * \param oneshot If true, this timer will only fire once
   * \param autostart If true (default), return timer that is already started
   */
  template<class T>
  Timer createTimer(Duration period, void(T::*callback)(const TimerEvent&), const boost::shared_ptr<T>& obj, 
                    bool oneshot = false, bool autostart = true) const
  {
    TimerOptions ops(period, boost::bind(callback, obj.get(), _1), 0);
    ops.tracked_object = obj;
    ops.oneshot = oneshot;
    ops.autostart = autostart;
    return createTimer(ops);
  }

  /**
   * \brief Create a timer which will call a callback at the specified rate.  This variant takes
   * anything that can be bound to a Boost.Function, including a bare function
   *
   * When the Timer (and all copies of it) returned goes out of scope, the timer will automatically
   * be stopped, and the callback will no longer be called.
   *
   * \param period The period at which to call the callback
   * \param callback The function to call
   * \param oneshot If true, this timer will only fire once
   * \param autostart If true (default), return timer that is already started
   */
  Timer createTimer(Duration period, const TimerCallback& callback, bool oneshot = false,
                    bool autostart = true) const;

  /**
   * \brief Create a timer which will call a callback at the specified rate.  This variant allows
   * the full range of TimerOptions.
   *
   * When the Timer (and all copies of it) returned goes out of scope, the timer will automatically
   * be stopped, and the callback will no longer be called.
   *
   * \param ops The options to use when creating the timer
   */
  Timer createTimer(TimerOptions& ops) const;

  //////////////////////////////////////////////////////////////////////////////////////////////////////////////
  // Versions of createWallTimer()
  //////////////////////////////////////////////////////////////////////////////////////////////////////////////

  /**
   * \brief Create a timer which will call a callback at the specified rate, using wall time to determine
   * when to call the callback instead of ROS time.
   * This variant takes a class member function, and a bare pointer to the object to call the method on.
   *
   * When the Timer (and all copies of it) returned goes out of scope, the timer will automatically
   * be stopped, and the callback will no longer be called.
   *
   * \param period The period at which to call the callback
   * \param callback The method to call
   * \param obj The object to call the method on
   * \param oneshot If true, this timer will only fire once
   * \param autostart If true (default), return timer that is already started
   */
  template<class T>
  WallTimer createWallTimer(WallDuration period, void(T::*callback)(const WallTimerEvent&), T* obj, 
                            bool oneshot = false, bool autostart = true) const
  {
    return createWallTimer(period, boost::bind(callback, obj, _1), oneshot, autostart);
  }

  /**
   * \brief Create a timer which will call a callback at the specified rate, using wall time to determine
   * when to call the callback instead of ROS time.  This variant takes
   * a class member function, and a shared pointer to the object to call the method on.
   *
   * When the Timer (and all copies of it) returned goes out of scope, the timer will automatically
   * be stopped, and the callback will no longer be called.
   *
   * \param period The period at which to call the callback
   * \param callback The method to call
   * \param obj The object to call the method on.  Since this is a shared pointer, the object will
   * automatically be tracked with a weak_ptr so that if it is deleted before the Timer goes out of
   * scope the callback will no longer be called (and therefore will not crash).
   * \param oneshot If true, this timer will only fire once
   */
  template<class T>
  WallTimer createWallTimer(WallDuration period, void(T::*callback)(const WallTimerEvent&), 
                            const boost::shared_ptr<T>& obj, 
                            bool oneshot = false, bool autostart = true) const
  {
    WallTimerOptions ops(period, boost::bind(callback, obj.get(), _1), 0);
    ops.tracked_object = obj;
    ops.oneshot = oneshot;
    ops.autostart = autostart;
    return createWallTimer(ops);
  }

  /**
   * \brief Create a timer which will call a callback at the specified rate, using wall time to determine
   * when to call the callback instead of ROS time.  This variant takes
   * anything that can be bound to a Boost.Function, including a bare function
   *
   * When the Timer (and all copies of it) returned goes out of scope, the timer will automatically
   * be stopped, and the callback will no longer be called.
   *
   * \param period The period at which to call the callback
   * \param callback The function to call
   * \param oneshot If true, this timer will only fire once
   */
  WallTimer createWallTimer(WallDuration period, const WallTimerCallback& callback, 
                            bool oneshot = false, bool autostart = true) const;

  /**
   * \brief Create a timer which will call a callback at the specified rate, using wall time to determine
   * when to call the callback instead of ROS time.  This variant allows
   * the full range of TimerOptions.
   *
   * When the Timer (and all copies of it) returned goes out of scope, the timer will automatically
   * be stopped, and the callback will no longer be called.
   *
   * \param ops The options to use when creating the timer
   */
  WallTimer createWallTimer(WallTimerOptions& ops) const;

  /** \brief Set an arbitrary XML/RPC value on the parameter server.
   *
   * \param key The key to be used in the parameter server's dictionary
   * \param v The value to be inserted.
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  void setParam(const std::string& key, const XmlRpc::XmlRpcValue& v) const;
  /** \brief Set a string value on the parameter server.
   *
   * \param key The key to be used in the parameter server's dictionary
   * \param s The value to be inserted.
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  void setParam(const std::string& key, const std::string& s) const;
  /** \brief Set a string value on the parameter server.
   *
   * \param key The key to be used in the parameter server's dictionary
   * \param s The value to be inserted.
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  void setParam(const std::string& key, const char* s) const;
  /** \brief Set a double value on the parameter server.
   *
   * \param key The key to be used in the parameter server's dictionary
   * \param d The value to be inserted.
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  void setParam(const std::string& key, double d) const;
  /** \brief Set an integer value on the parameter server.
   *
   * \param key The key to be used in the parameter server's dictionary
   * \param i The value to be inserted.
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  void setParam(const std::string& key, int i) const;
  /** \brief Set a boolean value on the parameter server.
   *
   * \param key The key to be used in the parameter server's dictionary
   * \param b The value to be inserted.
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  void setParam(const std::string& key, bool b) const;

  /** \brief Set a string vector value on the parameter server.
   *
   * \param key The key to be used in the parameter server's dictionary
   * \param vec The value to be inserted.
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  void setParam(const std::string& key, const std::vector<std::string>& vec) const;
  /** \brief Set a double vector value on the parameter server.
   *
   * \param key The key to be used in the parameter server's dictionary
   * \param vec The value to be inserted.
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  void setParam(const std::string& key, const std::vector<double>& vec) const;
  /** \brief Set a float vector value on the parameter server.
   *
   * \param key The key to be used in the parameter server's dictionary
   * \param vec The value to be inserted.
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  void setParam(const std::string& key, const std::vector<float>& vec) const;
  /** \brief Set a int vector value on the parameter server.
   *
   * \param key The key to be used in the parameter server's dictionary
   * \param vec The value to be inserted.
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  void setParam(const std::string& key, const std::vector<int>& vec) const;
  /** \brief Set a bool vector value on the parameter server.
   *
   * \param key The key to be used in the parameter server's dictionary
   * \param vec The value to be inserted.
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  void setParam(const std::string& key, const std::vector<bool>& vec) const;

  /** \brief Set a string vector value on the parameter server.
   *
   * \param key The key to be used in the parameter server's dictionary
   * \param map The value to be inserted.
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  void setParam(const std::string& key, const std::map<std::string, std::string>& map) const;
  /** \brief Set a double vector value on the parameter server.
   *
   * \param key The key to be used in the parameter server's dictionary
   * \param map The value to be inserted.
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  void setParam(const std::string& key, const std::map<std::string, double>& map) const;
  /** \brief Set a float vector value on the parameter server.
   *
   * \param key The key to be used in the parameter server's dictionary
   * \param map The value to be inserted.
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  void setParam(const std::string& key, const std::map<std::string, float>& map) const;
  /** \brief Set a int vector value on the parameter server.
   *
   * \param key The key to be used in the parameter server's dictionary
   * \param map The value to be inserted.
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  void setParam(const std::string& key, const std::map<std::string, int>& map) const;
  /** \brief Set a bool vector value on the parameter server.
   *
   * \param key The key to be used in the parameter server's dictionary
   * \param map The value to be inserted.
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  void setParam(const std::string& key, const std::map<std::string, bool>& map) const;

  /** \brief Get a string value from the parameter server.
   *
   * \param key The key to be used in the parameter server's dictionary
   * \param[out] s Storage for the retrieved value.
   *
   * \return true if the parameter value was retrieved, false otherwise
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  bool getParam(const std::string& key, std::string& s) const;
  /** \brief Get a double value from the parameter server.
   *
   * If you want to provide a default value in case the key does not exist use param().
   *
   * \param key The key to be used in the parameter server's dictionary
   * \param[out] d Storage for the retrieved value.
   *
   * \return true if the parameter value was retrieved, false otherwise
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  bool getParam(const std::string& key, double& d) const;
  /** \brief Get a float value from the parameter server.
   *
   * If you want to provide a default value in case the key does not exist use param().
   *
   * \param key The key to be used in the parameter server's dictionary
   * \param[out] f Storage for the retrieved value.
   *
   * \return true if the parameter value was retrieved, false otherwise
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  bool getParam(const std::string& key, float& f) const;
  /** \brief Get an integer value from the parameter server.
   *
   * If you want to provide a default value in case the key does not exist use param().
   *
   * \param key The key to be used in the parameter server's dictionary
   * \param[out] i Storage for the retrieved value.
   *
   * \return true if the parameter value was retrieved, false otherwise
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  bool getParam(const std::string& key, int& i) const;
  /** \brief Get a boolean value from the parameter server.
   *
   * If you want to provide a default value in case the key does not exist use param().
   *
   * \param key The key to be used in the parameter server's dictionary
   * \param[out] b Storage for the retrieved value.
   *
   * \return true if the parameter value was retrieved, false otherwise
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  bool getParam(const std::string& key, bool& b) const;
  /** \brief Get an arbitrary XML/RPC value from the parameter server.
   *
   * If you want to provide a default value in case the key does not exist use param().
   *
   * \param key The key to be used in the parameter server's dictionary
   * \param[out] v Storage for the retrieved value.
   *
   * \return true if the parameter value was retrieved, false otherwise
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  bool getParam(const std::string& key, XmlRpc::XmlRpcValue& v) const;

  /** \brief Get a string vector value from the parameter server.
   *
   * If you want to provide a default value in case the key does not exist use param().
   *
   * \param key The key to be used in the parameter server's dictionary
   * \param[out] vec Storage for the retrieved value.
   *
   * \return true if the parameter value was retrieved, false otherwise
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  bool getParam(const std::string& key, std::vector<std::string>& vec) const;
  /** \brief Get a double vector value from the parameter server.
   *
   * If you want to provide a default value in case the key does not exist use param().
   *
   * \param key The key to be used in the parameter server's dictionary
   * \param[out] vec Storage for the retrieved value.
   *
   * \return true if the parameter value was retrieved, false otherwise
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  bool getParam(const std::string& key, std::vector<double>& vec) const;
  /** \brief Get a float vector value from the parameter server.
   *
   * If you want to provide a default value in case the key does not exist use param().
   *
   * \param key The key to be used in the parameter server's dictionary
   * \param[out] vec Storage for the retrieved value.
   *
   * \return true if the parameter value was retrieved, false otherwise
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  bool getParam(const std::string& key, std::vector<float>& vec) const;
  /** \brief Get an int vector value from the parameter server.
   *
   * If you want to provide a default value in case the key does not exist use param().
   *
   * \param key The key to be used in the parameter server's dictionary
   * \param[out] vec Storage for the retrieved value.
   *
   * \return true if the parameter value was retrieved, false otherwise
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  bool getParam(const std::string& key, std::vector<int>& vec) const;
  /** \brief Get a boolean vector value from the parameter server.
   *
   * If you want to provide a default value in case the key does not exist use param().
   *
   * \param key The key to be used in the parameter server's dictionary
   * \param[out] vec Storage for the retrieved value.
   *
   * \return true if the parameter value was retrieved, false otherwise
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  bool getParam(const std::string& key, std::vector<bool>& vec) const;

  /** \brief Get a string map value from the parameter server.
   *
   * If you want to provide a default value in case the key does not exist use param().
   *
   * \param key The key to be used in the parameter server's dictionary
   * \param[out] map Storage for the retrieved value.
   *
   * \return true if the parameter value was retrieved, false otherwise
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  bool getParam(const std::string& key, std::map<std::string, std::string>& map) const;
  /** \brief Get a double map value from the parameter server.
   *
   * If you want to provide a default value in case the key does not exist use param().
   *
   * \param key The key to be used in the parameter server's dictionary
   * \param[out] map Storage for the retrieved value.
   *
   * \return true if the parameter value was retrieved, false otherwise
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  bool getParam(const std::string& key, std::map<std::string, double>& map) const;
  /** \brief Get a float map value from the parameter server.
   *
   * If you want to provide a default value in case the key does not exist use param().
   *
   * \param key The key to be used in the parameter server's dictionary
   * \param[out] map Storage for the retrieved value.
   *
   * \return true if the parameter value was retrieved, false otherwise
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  bool getParam(const std::string& key, std::map<std::string, float>& map) const;
  /** \brief Get an int map value from the parameter server.
   *
   * If you want to provide a default value in case the key does not exist use param().
   *
   * \param key The key to be used in the parameter server's dictionary
   * \param[out] map Storage for the retrieved value.
   *
   * \return true if the parameter value was retrieved, false otherwise
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  bool getParam(const std::string& key, std::map<std::string, int>& map) const;
  /** \brief Get a boolean map value from the parameter server.
   *
   * If you want to provide a default value in case the key does not exist use param().
   *
   * \param key The key to be used in the parameter server's dictionary
   * \param[out] map Storage for the retrieved value.
   *
   * \return true if the parameter value was retrieved, false otherwise
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  bool getParam(const std::string& key, std::map<std::string, bool>& map) const;

  /** \brief Get a string value from the parameter server, with local caching
   *
   * If you want to provide a default value in case the key does not exist use param().
   *
   * This method will cache parameters locally, and subscribe for updates from
   * the parameter server.  Once the parameter is retrieved for the first time
   * no subsequent getCached() calls with the same key will query the master --
   * they will instead look up in the local cache.
   *
   * \param key The key to be used in the parameter server's dictionary
   * \param[out] s Storage for the retrieved value.
   *
   * \return true if the parameter value was retrieved, false otherwise
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  bool getParamCached(const std::string& key, std::string& s) const;
  /** \brief Get a double value from the parameter server, with local caching
   *
   * This method will cache parameters locally, and subscribe for updates from
   * the parameter server.  Once the parameter is retrieved for the first time
   * no subsequent getCached() calls with the same key will query the master --
   * they will instead look up in the local cache.
   *
   * \param key The key to be used in the parameter server's dictionary
   * \param[out] d Storage for the retrieved value.
   *
   * \return true if the parameter value was retrieved, false otherwise
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  bool getParamCached(const std::string& key, double& d) const;
  /** \brief Get a float value from the parameter server, with local caching
   *
   * This method will cache parameters locally, and subscribe for updates from
   * the parameter server.  Once the parameter is retrieved for the first time
   * no subsequent getCached() calls with the same key will query the master --
   * they will instead look up in the local cache.
   *
   * \param key The key to be used in the parameter server's dictionary
   * \param[out] f Storage for the retrieved value.
   *
   * \return true if the parameter value was retrieved, false otherwise
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  bool getParamCached(const std::string& key, float& f) const;
  /** \brief Get an integer value from the parameter server, with local caching
   *
   * This method will cache parameters locally, and subscribe for updates from
   * the parameter server.  Once the parameter is retrieved for the first time
   * no subsequent getCached() calls with the same key will query the master --
   * they will instead look up in the local cache.
   *
   * \param key The key to be used in the parameter server's dictionary
   * \param[out] i Storage for the retrieved value.
   *
   * \return true if the parameter value was retrieved, false otherwise
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  bool getParamCached(const std::string& key, int& i) const;
  /** \brief Get a boolean value from the parameter server, with local caching
   *
   * This method will cache parameters locally, and subscribe for updates from
   * the parameter server.  Once the parameter is retrieved for the first time
   * no subsequent getCached() calls with the same key will query the master --
   * they will instead look up in the local cache.
   *
   * \param key The key to be used in the parameter server's dictionary
   * \param[out] b Storage for the retrieved value.
   *
   * \return true if the parameter value was retrieved, false otherwise
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  bool getParamCached(const std::string& key, bool& b) const;
  /** \brief Get an arbitrary XML/RPC value from the parameter server, with local caching
   *
   * This method will cache parameters locally, and subscribe for updates from
   * the parameter server.  Once the parameter is retrieved for the first time
   * no subsequent getCached() calls with the same key will query the master --
   * they will instead look up in the local cache.
   *
   * \param key The key to be used in the parameter server's dictionary
   * \param[out] v Storage for the retrieved value.
   *
   * \return true if the parameter value was retrieved, false otherwise
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  bool getParamCached(const std::string& key, XmlRpc::XmlRpcValue& v) const;

  /** \brief Get a std::string vector value from the parameter server, with local caching
   *
   * This method will cache parameters locally, and subscribe for updates from
   * the parameter server.  Once the parameter is retrieved for the first time
   * no subsequent getCached() calls with the same key will query the master --
   * they will instead look up in the local cache.
   *
   * \param key The key to be used in the parameter server's dictionary
   * \param[out] vec Storage for the retrieved value.
   *
   * \return true if the parameter value was retrieved, false otherwise
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  bool getParamCached(const std::string& key, std::vector<std::string>& vec) const;
  /** \brief Get a double vector value from the parameter server, with local caching
   *
   * This method will cache parameters locally, and subscribe for updates from
   * the parameter server.  Once the parameter is retrieved for the first time
   * no subsequent getCached() calls with the same key will query the master --
   * they will instead look up in the local cache.
   *
   * \param key The key to be used in the parameter server's dictionary
   * \param[out] vec Storage for the retrieved value.
   *
   * \return true if the parameter value was retrieved, false otherwise
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  bool getParamCached(const std::string& key, std::vector<double>& vec) const;
  /** \brief Get a float vector value from the parameter server, with local caching
   *
   * This method will cache parameters locally, and subscribe for updates from
   * the parameter server.  Once the parameter is retrieved for the first time
   * no subsequent getCached() calls with the same key will query the master --
   * they will instead look up in the local cache.
   *
   * \param key The key to be used in the parameter server's dictionary
   * \param[out] vec Storage for the retrieved value.
   *
   * \return true if the parameter value was retrieved, false otherwise
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  bool getParamCached(const std::string& key, std::vector<float>& vec) const;
  /** \brief Get a int vector value from the parameter server, with local caching
   *
   * This method will cache parameters locally, and subscribe for updates from
   * the parameter server.  Once the parameter is retrieved for the first time
   * no subsequent getCached() calls with the same key will query the master --
   * they will instead look up in the local cache.
   *
   * \param key The key to be used in the parameter server's dictionary
   * \param[out] vec Storage for the retrieved value.
   *
   * \return true if the parameter value was retrieved, false otherwise
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  bool getParamCached(const std::string& key, std::vector<int>& vec) const;
  /** \brief Get a bool vector value from the parameter server, with local caching
   *
   * This method will cache parameters locally, and subscribe for updates from
   * the parameter server.  Once the parameter is retrieved for the first time
   * no subsequent getCached() calls with the same key will query the master --
   * they will instead look up in the local cache.
   *
   * \param key The key to be used in the parameter server's dictionary
   * \param[out] vec Storage for the retrieved value.
   *
   * \return true if the parameter value was retrieved, false otherwise
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  bool getParamCached(const std::string& key, std::vector<bool>& vec) const;

  /** \brief Get a string->std::string map value from the parameter server, with local caching
   *
   * This method will cache parameters locally, and subscribe for updates from
   * the parameter server.  Once the parameter is retrieved for the first time
   * no subsequent getCached() calls with the same key will query the master --
   * they will instead look up in the local cache.
   *
   * \param key The key to be used in the parameter server's dictionary
   * \param[out] map Storage for the retrieved value.
   *
   * \return true if the parameter value was retrieved, false otherwise
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  bool getParamCached(const std::string& key, std::map<std::string, std::string>& map) const;
  /** \brief Get a string->double map value from the parameter server, with local caching
   *
   * This method will cache parameters locally, and subscribe for updates from
   * the parameter server.  Once the parameter is retrieved for the first time
   * no subsequent getCached() calls with the same key will query the master --
   * they will instead look up in the local cache.
   *
   * \param key The key to be used in the parameter server's dictionary
   * \param[out] map Storage for the retrieved value.
   *
   * \return true if the parameter value was retrieved, false otherwise
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  bool getParamCached(const std::string& key, std::map<std::string, double>& map) const;
  /** \brief Get a string->float map value from the parameter server, with local caching
   *
   * This method will cache parameters locally, and subscribe for updates from
   * the parameter server.  Once the parameter is retrieved for the first time
   * no subsequent getCached() calls with the same key will query the master --
   * they will instead look up in the local cache.
   *
   * \param key The key to be used in the parameter server's dictionary
   * \param[out] map Storage for the retrieved value.
   *
   * \return true if the parameter value was retrieved, false otherwise
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  bool getParamCached(const std::string& key, std::map<std::string, float>& map) const;
  /** \brief Get a string->int map value from the parameter server, with local caching
   *
   * This method will cache parameters locally, and subscribe for updates from
   * the parameter server.  Once the parameter is retrieved for the first time
   * no subsequent getCached() calls with the same key will query the master --
   * they will instead look up in the local cache.
   *
   * \param key The key to be used in the parameter server's dictionary
   * \param[out] map Storage for the retrieved value.
   *
   * \return true if the parameter value was retrieved, false otherwise
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  bool getParamCached(const std::string& key, std::map<std::string, int>& map) const;
  /** \brief Get a string->bool map value from the parameter server, with local caching
   *
   * This method will cache parameters locally, and subscribe for updates from
   * the parameter server.  Once the parameter is retrieved for the first time
   * no subsequent getCached() calls with the same key will query the master --
   * they will instead look up in the local cache.
   *
   * \param key The key to be used in the parameter server's dictionary
   * \param[out] map Storage for the retrieved value.
   *
   * \return true if the parameter value was retrieved, false otherwise
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  bool getParamCached(const std::string& key, std::map<std::string, bool>& map) const;

  /** \brief Check whether a parameter exists on the parameter server.
   *
   * \param key The key to check.
   *
   * \return true if the parameter exists, false otherwise
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  bool hasParam(const std::string& key) const;
  /** \brief Search up the tree for a parameter with a given key
   *
   * This function parameter server's searchParam feature to search up the tree for
   * a parameter.  For example, if the parameter server has a parameter [/a/b]
   * and you're in the namespace [/a/c/d], searching for the parameter "b" will
   * yield [/a/b].  If [/a/c/d/b] existed, that parameter would be returned instead.
   *
   * \param key the parameter to search for
   * \param [out] result the found value (if any)
   *
   * \return true if the parameter was found, false otherwise.
   */
  bool searchParam(const std::string& key, std::string& result) const;
  /** \brief Delete a parameter from the parameter server.
   *
   * \param key The key to delete.
   *
   * \return true if the deletion succeeded, false otherwise.
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  bool deleteParam(const std::string& key) const;

  /** \brief Assign value from parameter server, with default.
   *
   * This method tries to retrieve the indicated parameter value from the
   * parameter server, storing the result in param_val.  If the value
   * cannot be retrieved from the server, default_val is used instead.
   *
   * \param param_name The key to be searched on the parameter server.
   * \param[out] param_val Storage for the retrieved value.
   * \param default_val Value to use if the server doesn't contain this
   * parameter.
   * \throws InvalidNameException If the parameter key begins with a tilde, or is an otherwise invalid graph resource name
   */
  template<typename T>
  void param(const std::string& param_name, T& param_val, const T& default_val) const
  {
    if (hasParam(param_name))
    {
      if (getParam(param_name, param_val))
      {
        return;
      }
    }

    param_val = default_val;
  }

  /**
   * \brief Return value from parameter server, or default if unavailable.
   *
   * This method tries to retrieve the indicated parameter value from the
   * parameter server. If the parameter cannot be retrieved, \c default_val
   * is returned instead.
   *
   * \param param_name The key to be searched on the parameter server.
   *
   * \param default_val Value to return if the server doesn't contain this
   * parameter.
   *
   * \return The parameter value retrieved from the parameter server, or
   * \c default_val if unavailable.
   *
   * \throws InvalidNameException If the parameter key begins with a tilde,
   * or is an otherwise invalid graph resource name.
   */
  template<typename T>
  T param(const std::string& param_name, const T& default_val)
  {
      T param_val;
      param(param_name, param_val, default_val);
      return param_val;
  }

  /**
   * \brief Shutdown every handle created through this NodeHandle.
   *
   * This method will unadvertise every topic and service advertisement,
   * and unsubscribe every subscription created through this NodeHandle.
   */
  void shutdown();

  /** \brief Check whether it's time to exit.
   *
   * This method checks to see if both ros::ok() is true and shutdown() has not been called on this NodeHandle, to see whether it's yet time
   * to exit.  ok() is false once either ros::shutdown() or NodeHandle::shutdown() have been called
   *
   * \return true if we're still OK, false if it's time to exit
   */
  bool ok() const;

private:
  struct no_validate { };
  // this is pretty awful, but required to preserve public interface (and make minimum possible changes)
  std::string resolveName(const std::string& name, bool remap, no_validate) const;

  void construct(const std::string& ns, bool validate_name);
  void destruct();

  void initRemappings(const M_string& remappings);

  std::string remapName(const std::string& name) const;

  std::string namespace_;
  std::string unresolved_namespace_;
  M_string remappings_;
  M_string unresolved_remappings_;

  CallbackQueueInterface* callback_queue_;

  NodeHandleBackingCollection* collection_;

  bool ok_;
};

}

#endif // ROSCPP_NODE_HANDLE_H