-
Notifications
You must be signed in to change notification settings - Fork 912
/
node_handle.h
1968 lines (1878 loc) · 89.7 KB
/
node_handle.h
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
/*
* 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 <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
if (handle)
{
...
}
\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
if (handle)
{
...
}
\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
if (handle)
{
...
}
\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
if (handle)
{
...
}
\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
if (handle)
{
...
}
\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
if (handle)
{
...
}
\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
if (handle)
{
...
}
\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
if (handle)
{
...
}
\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
if (handle)
{
...
}
\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
if (handle)
{
...
}
\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
if (handle)
{
...
}
\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
if (handle)
{
...
}
\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
if (handle)
{
...
}
\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
if (handle)
{
...
}
\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
if (handle)
{
...
}
\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
if (handle)
{
...
}
\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.