-
Notifications
You must be signed in to change notification settings - Fork 409
/
node.hpp
1666 lines (1568 loc) · 69.1 KB
/
node.hpp
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 2014 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef RCLCPP__NODE_HPP_
#define RCLCPP__NODE_HPP_
#include <atomic>
#include <condition_variable>
#include <functional>
#include <list>
#include <map>
#include <memory>
#include <mutex>
#include <string>
#include <tuple>
#include <utility>
#include <vector>
#include "rcutils/macros.h"
#include "rcl/error_handling.h"
#include "rcl/node.h"
#include "rcl_interfaces/msg/list_parameters_result.hpp"
#include "rcl_interfaces/msg/parameter_descriptor.hpp"
#include "rcl_interfaces/msg/parameter_event.hpp"
#include "rcl_interfaces/msg/set_parameters_result.hpp"
#include "rclcpp/callback_group.hpp"
#include "rclcpp/client.hpp"
#include "rclcpp/clock.hpp"
#include "rclcpp/context.hpp"
#include "rclcpp/event.hpp"
#include "rclcpp/generic_client.hpp"
#include "rclcpp/generic_publisher.hpp"
#include "rclcpp/generic_subscription.hpp"
#include "rclcpp/logger.hpp"
#include "rclcpp/macros.hpp"
#include "rclcpp/message_memory_strategy.hpp"
#include "rclcpp/node_interfaces/node_base_interface.hpp"
#include "rclcpp/node_interfaces/node_clock_interface.hpp"
#include "rclcpp/node_interfaces/node_graph_interface.hpp"
#include "rclcpp/node_interfaces/node_logging_interface.hpp"
#include "rclcpp/node_interfaces/node_parameters_interface.hpp"
#include "rclcpp/node_interfaces/node_services_interface.hpp"
#include "rclcpp/node_interfaces/node_time_source_interface.hpp"
#include "rclcpp/node_interfaces/node_timers_interface.hpp"
#include "rclcpp/node_interfaces/node_topics_interface.hpp"
#include "rclcpp/node_interfaces/node_type_descriptions_interface.hpp"
#include "rclcpp/node_interfaces/node_waitables_interface.hpp"
#include "rclcpp/node_options.hpp"
#include "rclcpp/parameter.hpp"
#include "rclcpp/publisher.hpp"
#include "rclcpp/publisher_options.hpp"
#include "rclcpp/qos.hpp"
#include "rclcpp/service.hpp"
#include "rclcpp/subscription.hpp"
#include "rclcpp/subscription_options.hpp"
#include "rclcpp/subscription_traits.hpp"
#include "rclcpp/time.hpp"
#include "rclcpp/timer.hpp"
#include "rclcpp/visibility_control.hpp"
namespace rclcpp
{
/// Node is the single point of entry for creating publishers and subscribers.
class Node : public std::enable_shared_from_this<Node>
{
public:
RCLCPP_SMART_PTR_DEFINITIONS(Node)
/// Create a new node with the specified name.
/**
* \param[in] node_name Name of the node.
* \param[in] options Additional options to control creation of the node.
* \throws InvalidNamespaceError if the namespace is invalid
*/
RCLCPP_PUBLIC
explicit Node(
const std::string & node_name,
const NodeOptions & options = NodeOptions());
/// Create a new node with the specified name.
/**
* \param[in] node_name Name of the node.
* \param[in] namespace_ Namespace of the node.
* \param[in] options Additional options to control creation of the node.
* \throws InvalidNamespaceError if the namespace is invalid
*/
RCLCPP_PUBLIC
explicit Node(
const std::string & node_name,
const std::string & namespace_,
const NodeOptions & options = NodeOptions());
RCLCPP_PUBLIC
virtual ~Node();
/// Get the name of the node.
/** \return The name of the node. */
RCLCPP_PUBLIC
const char *
get_name() const;
/// Get the namespace of the node.
/**
* This namespace is the "node's" namespace, and therefore is not affected
* by any sub-namespace's that may affect entities created with this instance.
* Use get_effective_namespace() to get the full namespace used by entities.
*
* \sa get_sub_namespace()
* \sa get_effective_namespace()
* \return The namespace of the node.
*/
RCLCPP_PUBLIC
const char *
get_namespace() const;
/// Get the fully-qualified name of the node.
/**
* The fully-qualified name includes the local namespace and name of the node.
* \return fully-qualified name of the node.
*/
RCLCPP_PUBLIC
const char *
get_fully_qualified_name() const;
/// Get the logger of the node.
/** \return The logger of the node. */
RCLCPP_PUBLIC
rclcpp::Logger
get_logger() const;
/// Create and return a callback group.
RCLCPP_PUBLIC
rclcpp::CallbackGroup::SharedPtr
create_callback_group(
rclcpp::CallbackGroupType group_type,
bool automatically_add_to_executor_with_node = true);
/// Iterate over the callback groups in the node, calling the given function on each valid one.
/**
* This method is called in a thread-safe way, and also makes sure to only call the given
* function on those items that are still valid.
*
* \param[in] func The callback function to call on each valid callback group.
*/
RCLCPP_PUBLIC
void
for_each_callback_group(const node_interfaces::NodeBaseInterface::CallbackGroupFunction & func);
/// Create and return a Publisher.
/**
* The rclcpp::QoS has several convenient constructors, including a
* conversion constructor for size_t, which mimics older API's that
* allows just a string and size_t to create a publisher.
*
* For example, all of these cases will work:
*
* ```cpp
* pub = node->create_publisher<MsgT>("chatter", 10); // implicitly KeepLast
* pub = node->create_publisher<MsgT>("chatter", QoS(10)); // implicitly KeepLast
* pub = node->create_publisher<MsgT>("chatter", QoS(KeepLast(10)));
* pub = node->create_publisher<MsgT>("chatter", QoS(KeepAll()));
* pub = node->create_publisher<MsgT>("chatter", QoS(1).best_effort().durability_volatile());
* {
* rclcpp::QoS custom_qos(KeepLast(10), rmw_qos_profile_sensor_data);
* pub = node->create_publisher<MsgT>("chatter", custom_qos);
* }
* ```
*
* The publisher options may optionally be passed as the third argument for
* any of the above cases.
*
* \param[in] topic_name The topic for this publisher to publish on.
* \param[in] qos The Quality of Service settings for the publisher.
* \param[in] options Additional options for the created Publisher.
* \return Shared pointer to the created publisher.
*/
template<
typename MessageT,
typename AllocatorT = std::allocator<void>,
typename PublisherT = rclcpp::Publisher<MessageT, AllocatorT>>
std::shared_ptr<PublisherT>
create_publisher(
const std::string & topic_name,
const rclcpp::QoS & qos,
const PublisherOptionsWithAllocator<AllocatorT> & options =
PublisherOptionsWithAllocator<AllocatorT>()
);
/// Create and return a Subscription.
/**
* \param[in] topic_name The topic to subscribe on.
* \param[in] qos QoS profile for Subcription.
* \param[in] callback The user-defined callback function to receive a message
* \param[in] options Additional options for the creation of the Subscription.
* \param[in] msg_mem_strat The message memory strategy to use for allocating messages.
* \return Shared pointer to the created subscription.
*/
template<
typename MessageT,
typename CallbackT,
typename AllocatorT = std::allocator<void>,
typename SubscriptionT = rclcpp::Subscription<MessageT, AllocatorT>,
typename MessageMemoryStrategyT = typename SubscriptionT::MessageMemoryStrategyType
>
std::shared_ptr<SubscriptionT>
create_subscription(
const std::string & topic_name,
const rclcpp::QoS & qos,
CallbackT && callback,
const SubscriptionOptionsWithAllocator<AllocatorT> & options =
SubscriptionOptionsWithAllocator<AllocatorT>(),
typename MessageMemoryStrategyT::SharedPtr msg_mem_strat = (
MessageMemoryStrategyT::create_default()
)
);
/// Create a wall timer that uses the wall clock to drive the callback.
/**
* \param[in] period Time interval between triggers of the callback.
* \param[in] callback User-defined callback function.
* \param[in] group Callback group to execute this timer's callback in.
* \param[in] autostart The state of the clock on initialization.
*/
template<typename DurationRepT = int64_t, typename DurationT = std::milli, typename CallbackT>
typename rclcpp::WallTimer<CallbackT>::SharedPtr
create_wall_timer(
std::chrono::duration<DurationRepT, DurationT> period,
CallbackT callback,
rclcpp::CallbackGroup::SharedPtr group = nullptr,
bool autostart = true);
/// Create a timer that uses the node clock to drive the callback.
/**
* \param[in] period Time interval between triggers of the callback.
* \param[in] callback User-defined callback function.
* \param[in] group Callback group to execute this timer's callback in.
*/
template<typename DurationRepT = int64_t, typename DurationT = std::milli, typename CallbackT>
typename rclcpp::GenericTimer<CallbackT>::SharedPtr
create_timer(
std::chrono::duration<DurationRepT, DurationT> period,
CallbackT callback,
rclcpp::CallbackGroup::SharedPtr group = nullptr);
/// Create and return a Client.
/**
* \param[in] service_name The topic to service on.
* \param[in] qos_profile rmw_qos_profile_t Quality of service profile for client.
* \param[in] group Callback group to call the service.
* \return Shared pointer to the created client.
* \deprecated use rclcpp::QoS instead of rmw_qos_profile_t
*/
template<typename ServiceT>
[[deprecated("use rclcpp::QoS instead of rmw_qos_profile_t")]]
typename rclcpp::Client<ServiceT>::SharedPtr
create_client(
const std::string & service_name,
const rmw_qos_profile_t & qos_profile,
rclcpp::CallbackGroup::SharedPtr group = nullptr);
/// Create and return a Client.
/**
* \param[in] service_name The name on which the service is accessible.
* \param[in] qos Quality of service profile for client.
* \param[in] group Callback group to handle the reply to service calls.
* \return Shared pointer to the created client.
*/
template<typename ServiceT>
typename rclcpp::Client<ServiceT>::SharedPtr
create_client(
const std::string & service_name,
const rclcpp::QoS & qos = rclcpp::ServicesQoS(),
rclcpp::CallbackGroup::SharedPtr group = nullptr);
/// Create and return a Service.
/**
* \param[in] service_name The topic to service on.
* \param[in] callback User-defined callback function.
* \param[in] qos_profile rmw_qos_profile_t Quality of service profile for client.
* \param[in] group Callback group to call the service.
* \return Shared pointer to the created service.
* \deprecated use rclcpp::QoS instead of rmw_qos_profile_t
*/
template<typename ServiceT, typename CallbackT>
[[deprecated("use rclcpp::QoS instead of rmw_qos_profile_t")]]
typename rclcpp::Service<ServiceT>::SharedPtr
create_service(
const std::string & service_name,
CallbackT && callback,
const rmw_qos_profile_t & qos_profile,
rclcpp::CallbackGroup::SharedPtr group = nullptr);
/// Create and return a Service.
/**
* \param[in] service_name The topic to service on.
* \param[in] callback User-defined callback function.
* \param[in] qos Quality of service profile for the service.
* \param[in] group Callback group to call the service.
* \return Shared pointer to the created service.
*/
template<typename ServiceT, typename CallbackT>
typename rclcpp::Service<ServiceT>::SharedPtr
create_service(
const std::string & service_name,
CallbackT && callback,
const rclcpp::QoS & qos = rclcpp::ServicesQoS(),
rclcpp::CallbackGroup::SharedPtr group = nullptr);
/// Create and return a GenericClient.
/**
* \param[in] service_name The name on which the service is accessible.
* \param[in] service_type The name of service type, e.g. "std_srvs/srv/SetBool"
* \param[in] qos Quality of service profile for client.
* \param[in] group Callback group to handle the reply to service calls.
* \return Shared pointer to the created GenericClient.
*/
RCLCPP_PUBLIC
rclcpp::GenericClient::SharedPtr
create_generic_client(
const std::string & service_name,
const std::string & service_type,
const rclcpp::QoS & qos = rclcpp::ServicesQoS(),
rclcpp::CallbackGroup::SharedPtr group = nullptr);
/// Create and return a GenericPublisher.
/**
* The returned pointer will never be empty, but this function can throw various exceptions, for
* instance when the message's package can not be found on the AMENT_PREFIX_PATH.
*
* \param[in] topic_name Topic name
* \param[in] topic_type Topic type
* \param[in] qos %QoS settings
* \param options %Publisher options.
* Not all publisher options are currently respected, the only relevant options for this
* publisher are `event_callbacks`, `use_default_callbacks`, and `%callback_group`.
* \return Shared pointer to the created generic publisher.
*/
template<typename AllocatorT = std::allocator<void>>
std::shared_ptr<rclcpp::GenericPublisher> create_generic_publisher(
const std::string & topic_name,
const std::string & topic_type,
const rclcpp::QoS & qos,
const rclcpp::PublisherOptionsWithAllocator<AllocatorT> & options = (
rclcpp::PublisherOptionsWithAllocator<AllocatorT>()
)
);
/// Create and return a GenericSubscription.
/**
* The returned pointer will never be empty, but this function can throw various exceptions, for
* instance when the message's package can not be found on the AMENT_PREFIX_PATH.
*
* \param[in] topic_name Topic name
* \param[in] topic_type Topic type
* \param[in] qos %QoS settings
* \param[in] callback Callback for new messages of serialized form
* \param[in] options %Subscription options.
* Not all subscription options are currently respected, the only relevant options for this
* subscription are `event_callbacks`, `use_default_callbacks`, `ignore_local_publications`, and
* `%callback_group`.
* \return Shared pointer to the created generic subscription.
*/
template<
typename CallbackT,
typename AllocatorT = std::allocator<void>>
std::shared_ptr<rclcpp::GenericSubscription> create_generic_subscription(
const std::string & topic_name,
const std::string & topic_type,
const rclcpp::QoS & qos,
CallbackT && callback,
const rclcpp::SubscriptionOptionsWithAllocator<AllocatorT> & options = (
rclcpp::SubscriptionOptionsWithAllocator<AllocatorT>()
)
);
/// Declare and initialize a parameter, return the effective value.
/**
* This method is used to declare that a parameter exists on this node.
* If, at run-time, the user has provided an initial value then it will be
* set in this method, otherwise the given default_value will be set.
* In either case, the resulting value is returned, whether or not it is
* based on the default value or the user provided initial value.
*
* If no parameter_descriptor is given, then the default values from the
* message definition will be used, e.g. read_only will be false.
*
* The name and type in the given rcl_interfaces::msg::ParameterDescriptor
* are ignored, and should be specified using the name argument to this
* function and the default value's type instead.
*
* If `ignore_override` is `true`, the parameter override will be ignored.
*
* This method will result in any callback registered with
* `add_on_set_parameters_callback` and `add_post_set_parameters_callback`
* to be called for the parameter being set.
*
* If a callback was registered previously with `add_on_set_parameters_callback`,
* it will be called prior to setting the parameter for the node.
* If that callback prevents the initial value for the parameter from being
* set then rclcpp::exceptions::InvalidParameterValueException is thrown.
*
* If a callback was registered previously with `add_post_set_parameters_callback`,
* it will be called after setting the parameter successfully for the node.
*
* This method will _not_ result in any callbacks registered with
* `add_pre_set_parameters_callback` to be called.
*
* The returned reference will remain valid until the parameter is
* undeclared.
*
* \param[in] name The name of the parameter.
* \param[in] default_value An initial value to be used if at run-time user
* did not override it.
* \param[in] parameter_descriptor An optional, custom description for
* the parameter.
* \param[in] ignore_override When `true`, the parameter override is ignored.
* Default to `false`.
* \return A const reference to the value of the parameter.
* \throws rclcpp::exceptions::ParameterAlreadyDeclaredException if parameter
* has already been declared.
* \throws rclcpp::exceptions::InvalidParametersException if a parameter
* name is invalid.
* \throws rclcpp::exceptions::InvalidParameterValueException if initial
* value fails to be set.
* \throws rclcpp::exceptions::InvalidParameterTypeException
* if the type of the default value or override is wrong.
*/
RCLCPP_PUBLIC
const rclcpp::ParameterValue &
declare_parameter(
const std::string & name,
const rclcpp::ParameterValue & default_value,
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
rcl_interfaces::msg::ParameterDescriptor(),
bool ignore_override = false);
/// Declare and initialize a parameter, return the effective value.
/**
* Same as the previous one, but a default value is not provided and the user
* must provide a parameter override of the correct type.
*
* \param[in] name The name of the parameter.
* \param[in] type Desired type of the parameter, which will enforced at runtime.
* \param[in] parameter_descriptor An optional, custom description for
* the parameter.
* \param[in] ignore_override When `true`, the parameter override is ignored.
* Default to `false`.
* \return A const reference to the value of the parameter.
* \throws Same as the previous overload taking a default value.
* \throws rclcpp::exceptions::InvalidParameterTypeException
* if an override is not provided or the provided override is of the wrong type.
*/
RCLCPP_PUBLIC
const rclcpp::ParameterValue &
declare_parameter(
const std::string & name,
rclcpp::ParameterType type,
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
rcl_interfaces::msg::ParameterDescriptor{},
bool ignore_override = false);
/// Declare and initialize a parameter with a type.
/**
* See the non-templated declare_parameter() on this class for details.
*
* If the type of the default value, and therefore also the type of return
* value, differs from the initial value provided in the node options, then
* a rclcpp::exceptions::InvalidParameterTypeException may be thrown.
* To avoid this, use the declare_parameter() method which returns an
* rclcpp::ParameterValue instead.
*
* Note, this method cannot return a const reference, because extending the
* lifetime of a temporary only works recursively with member initializers,
* and cannot be extended to members of a class returned.
* The return value of this class is a copy of the member of a ParameterValue
* which is returned by the other version of declare_parameter().
* See also:
*
* - https://en.cppreference.com/w/cpp/language/lifetime
* - https://herbsutter.com/2008/01/01/gotw-88-a-candidate-for-the-most-important-const/
* - https://www.youtube.com/watch?v=uQyT-5iWUow (cppnow 2018 presentation)
*/
template<typename ParameterT>
auto
declare_parameter(
const std::string & name,
const ParameterT & default_value,
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
rcl_interfaces::msg::ParameterDescriptor(),
bool ignore_override = false);
/// Declare and initialize a parameter with a type.
/**
* See the non-templated declare_parameter() on this class for details.
*/
template<typename ParameterT>
auto
declare_parameter(
const std::string & name,
const rcl_interfaces::msg::ParameterDescriptor & parameter_descriptor =
rcl_interfaces::msg::ParameterDescriptor(),
bool ignore_override = false);
/// Declare and initialize several parameters with the same namespace and type.
/**
* For each key in the map, a parameter with a name of "namespace.key"
* will be set to the value in the map.
* The resulting value for each declared parameter will be returned.
*
* The name expansion is naive, so if you set the namespace to be "foo.",
* then the resulting parameter names will be like "foo..key".
* However, if the namespace is an empty string, then no leading '.' will be
* placed before each key, which would have been the case when naively
* expanding "namespace.key".
* This allows you to declare several parameters at once without a namespace.
*
* The map contains default values for parameters.
* There is another overload which takes the std::pair with the default value
* and descriptor.
*
* If `ignore_overrides` is `true`, all the overrides of the parameters declared
* by the function call will be ignored.
*
* This method will result in any callback registered with
* `add_on_set_parameters_callback` and `add_post_set_parameters_callback`
* to be called once for each parameter.
*
* This method, if successful, will result in any callback registered with
* `add_on_set_parameters_callback` to be called, once for each parameter.
* If that callback prevents the initial value for any parameter from being
* set then rclcpp::exceptions::InvalidParameterValueException is thrown.
*
* If a callback was registered previously with `add_post_set_parameters_callback`,
* it will be called after setting the parameters successfully for the node,
* once for each parameter.
*
* This method will _not_ result in any callbacks registered with
* `add_pre_set_parameters_callback` to be called.
*
* \param[in] namespace_ The namespace in which to declare the parameters.
* \param[in] parameters The parameters to set in the given namespace.
* \param[in] ignore_overrides When `true`, the parameters overrides are ignored.
* Default to `false`.
* \throws rclcpp::exceptions::ParameterAlreadyDeclaredException if parameter
* has already been declared.
* \throws rclcpp::exceptions::InvalidParametersException if a parameter
* name is invalid.
* \throws rclcpp::exceptions::InvalidParameterValueException if initial
* value fails to be set.
*/
template<typename ParameterT>
std::vector<ParameterT>
declare_parameters(
const std::string & namespace_,
const std::map<std::string, ParameterT> & parameters,
bool ignore_overrides = false);
/// Declare and initialize several parameters with the same namespace and type.
/**
* This version will take a map where the value is a pair, with the default
* parameter value as the first item and a parameter descriptor as the second.
*
* See the simpler declare_parameters() on this class for more details.
*/
template<typename ParameterT>
std::vector<ParameterT>
declare_parameters(
const std::string & namespace_,
const std::map<
std::string,
std::pair<ParameterT, rcl_interfaces::msg::ParameterDescriptor>
> & parameters,
bool ignore_overrides = false);
/// Undeclare a previously declared parameter.
/**
* This method will _not_ cause a callback registered with any of the
* `add_pre_set_parameters_callback`, `add_on_set_parameters_callback` and
* `add_post_set_parameters_callback` to be called.
*
* \param[in] name The name of the parameter to be undeclared.
* \throws rclcpp::exceptions::ParameterNotDeclaredException if the parameter
* has not been declared.
* \throws rclcpp::exceptions::ParameterImmutableException if the parameter
* was create as read_only (immutable).
*/
RCLCPP_PUBLIC
void
undeclare_parameter(const std::string & name);
/// Return true if a given parameter is declared.
/**
* \param[in] name The name of the parameter to check for being declared.
* \return true if the parameter name has been declared, otherwise false.
*/
RCLCPP_PUBLIC
bool
has_parameter(const std::string & name) const;
/// Set a single parameter.
/**
* Set the given parameter and then return result of the set action.
*
* If the parameter has not been declared this function may throw the
* rclcpp::exceptions::ParameterNotDeclaredException exception, but only if
* the node was not created with the
* rclcpp::NodeOptions::allow_undeclared_parameters set to true.
* If undeclared parameters are allowed, then the parameter is implicitly
* declared with the default parameter meta data before being set.
* Parameter overrides are ignored by set_parameter.
*
* This method will result in any callback registered with
* `add_pre_set_parameters_callback`, add_on_set_parameters_callback` and
* `add_post_set_parameters_callback` to be called once for the parameter
* being set.
*
* This method will result in any callback registered with
* `add_on_set_parameters_callback` to be called.
* If the callback prevents the parameter from being set, then it will be
* reflected in the SetParametersResult that is returned, but no exception
* will be thrown.
*
* If a callback was registered previously with `add_pre_set_parameters_callback`,
* it will be called once prior to the validation of the parameter for the node.
* If this callback makes modified parameter list empty, then it will be reflected
* in the returned result; no exceptions will be raised in this case.
*
* If a callback was registered previously with `add_post_set_parameters_callback`,
* it will be called once after setting the parameter successfully for the node.
*
* If the value type of the parameter is rclcpp::PARAMETER_NOT_SET, and the
* existing parameter type is something else, then the parameter will be
* implicitly undeclared.
* This will result in a parameter event indicating that the parameter was
* deleted.
*
* \param[in] parameter The parameter to be set.
* \return The result of the set action.
* \throws rclcpp::exceptions::ParameterNotDeclaredException if the parameter
* has not been declared and undeclared parameters are not allowed.
*/
RCLCPP_PUBLIC
rcl_interfaces::msg::SetParametersResult
set_parameter(const rclcpp::Parameter & parameter);
/// Set one or more parameters, one at a time.
/**
* Set the given parameters, one at a time, and then return result of each
* set action.
*
* Parameters are set in the order they are given within the input vector.
*
* Like set_parameter, if any of the parameters to be set have not first been
* declared, and undeclared parameters are not allowed (the default), then
* this method will throw rclcpp::exceptions::ParameterNotDeclaredException.
*
* If setting a parameter fails due to not being declared, then the
* parameters which have already been set will stay set, and no attempt will
* be made to set the parameters which come after.
*
* If a parameter fails to be set due to any other reason, like being
* rejected by the user's callback (basically any reason other than not
* having been declared beforehand), then that is reflected in the
* corresponding SetParametersResult in the vector returned by this function.
*
* This method will result in any callback registered with
* `add_pre_set_parameters_callback`, `add_on_set_parameters_callback` and
* `add_post_set_parameters_callback` to be called once for each parameter.
* If a callback was registered previously with `add_pre_set_parameters_callback`,
* it will be called prior to the validation of parameters for the node,
* once for each parameter.
* If this callback makes modified parameter list empty, then it will be reflected
* in the returned result; no exceptions will be raised in this case.
*
* This method will result in any callback registered with
* `add_on_set_parameters_callback` to be called, once for each parameter.
* If the callback prevents the parameter from being set, then, as mentioned
* before, it will be reflected in the corresponding SetParametersResult
* that is returned, but no exception will be thrown.
*
* If a callback was registered previously with `add_post_set_parameters_callback`,
* it will be called after setting the parameters successfully for the node,
* once for each parameter.
*
* Like set_parameter() this method will implicitly undeclare parameters
* with the type rclcpp::PARAMETER_NOT_SET.
*
* \param[in] parameters The vector of parameters to be set.
* \return The results for each set action as a vector.
* \throws rclcpp::exceptions::ParameterNotDeclaredException if any parameter
* has not been declared and undeclared parameters are not allowed.
*/
RCLCPP_PUBLIC
std::vector<rcl_interfaces::msg::SetParametersResult>
set_parameters(const std::vector<rclcpp::Parameter> & parameters);
/// Set one or more parameters, all at once.
/**
* Set the given parameters, all at one time, and then aggregate result.
*
* Behaves like set_parameter, except that it sets multiple parameters,
* failing all if just one of the parameters are unsuccessfully set.
* Either all of the parameters are set or none of them are set.
*
* Like set_parameter and set_parameters, this method may throw an
* rclcpp::exceptions::ParameterNotDeclaredException exception if any of the
* parameters to be set have not first been declared.
* If the exception is thrown then none of the parameters will have been set.
*
* This method will result in any callback registered with
* `add_pre_set_parameters_callback`, `add_on_set_parameters_callback` and
* `add_post_set_parameters_callback` to be called only 'once' for all parameters.
*
* If a callback was registered previously with `add_pre_set_parameters_callback`,
* it will be called prior to the validation of node parameters, just one time
* for all parameters.
* If this callback makes modified parameter list empty, then it will be reflected
* in the returned result; no exceptions will be raised in this case.
*
* This method will result in any callback registered with
* 'add_on_set_parameters_callback' to be called, just one time.
* If the callback prevents the parameters from being set, then it will be
* reflected in the SetParametersResult which is returned, but no exception
* will be thrown.
*
* If a callback was registered previously with `add_post_set_parameters_callback`,
* it will be called after setting the node parameters successfully, just one time
* for all parameters.
*
* If you pass multiple rclcpp::Parameter instances with the same name, then
* only the last one in the vector (forward iteration) will be set.
*
* Like set_parameter() this method will implicitly undeclare parameters
* with the type rclcpp::PARAMETER_NOT_SET.
*
* \param[in] parameters The vector of parameters to be set.
* \return The aggregate result of setting all the parameters atomically.
* \throws rclcpp::exceptions::ParameterNotDeclaredException if any parameter
* has not been declared and undeclared parameters are not allowed.
*/
RCLCPP_PUBLIC
rcl_interfaces::msg::SetParametersResult
set_parameters_atomically(const std::vector<rclcpp::Parameter> & parameters);
/// Return the parameter by the given name.
/**
* If the parameter has not been declared, then this method may throw the
* rclcpp::exceptions::ParameterNotDeclaredException exception.
* If the parameter has not been initialized, then this method may throw the
* rclcpp::exceptions::ParameterUninitializedException exception.
*
* If undeclared parameters are allowed, see the node option
* rclcpp::NodeOptions::allow_undeclared_parameters, then this method will
* not throw the rclcpp::exceptions::ParameterNotDeclaredException exception,
* and instead return a default initialized rclcpp::Parameter, which has a type of
* rclcpp::ParameterType::PARAMETER_NOT_SET.
*
* \param[in] name The name of the parameter to get.
* \return The requested parameter inside of a rclcpp parameter object.
* \throws rclcpp::exceptions::ParameterNotDeclaredException if the parameter
* has not been declared and undeclared parameters are not allowed.
* \throws rclcpp::exceptions::ParameterUninitializedException if the parameter
* has not been initialized.
*/
RCLCPP_PUBLIC
rclcpp::Parameter
get_parameter(const std::string & name) const;
/// Get the value of a parameter by the given name, and return true if it was set.
/**
* This method will never throw the
* rclcpp::exceptions::ParameterNotDeclaredException exception, but will
* instead return false if the parameter has not be previously declared.
*
* If the parameter was not declared, then the output argument for this
* method which is called "parameter" will not be assigned a value.
* If the parameter was declared, and therefore has a value, then it is
* assigned into the "parameter" argument of this method.
*
* \param[in] name The name of the parameter to get.
* \param[out] parameter The output storage for the parameter being retrieved.
* \return true if the parameter was previously declared, otherwise false.
*/
RCLCPP_PUBLIC
bool
get_parameter(const std::string & name, rclcpp::Parameter & parameter) const;
/// Get the value of a parameter by the given name, and return true if it was set.
/**
* Identical to the non-templated version of this method, except that when
* assigning the output argument called "parameter", this method will attempt
* to coerce the parameter value into the type requested by the given
* template argument, which may fail and throw an exception.
*
* If the parameter has not been declared, it will not attempt to coerce the
* value into the requested type, as it is known that the type is not set.
*
* \throws rclcpp::ParameterTypeException if the requested type does not
* match the value of the parameter which is stored.
*/
template<typename ParameterT>
bool
get_parameter(const std::string & name, ParameterT & parameter) const;
/// Get the parameter value, or the "alternative_value" if not set, and assign it to "parameter".
/**
* If the parameter was not set, then the "parameter" argument is assigned
* the "alternative_value".
*
* Like the version of get_parameter() which returns a bool, this method will
* not throw the rclcpp::exceptions::ParameterNotDeclaredException exception.
*
* In all cases, the parameter is never set or declared within the node.
*
* \param[in] name The name of the parameter to get.
* \param[out] parameter The output where the value of the parameter should be assigned.
* \param[in] alternative_value Value to be stored in output if the parameter was not set.
* \returns true if the parameter was set, false otherwise.
*/
template<typename ParameterT>
bool
get_parameter_or(
const std::string & name,
ParameterT & parameter,
const ParameterT & alternative_value) const;
/// Return the parameter value, or the "alternative_value" if not set.
/**
* If the parameter was not set, then the "alternative_value" argument is returned.
*
* This method will not throw the rclcpp::exceptions::ParameterNotDeclaredException exception.
*
* In all cases, the parameter is never set or declared within the node.
*
* \param[in] name The name of the parameter to get.
* \param[in] alternative_value Value to be stored in output if the parameter was not set.
* \returns The value of the parameter.
*/
template<typename ParameterT>
ParameterT
get_parameter_or(
const std::string & name,
const ParameterT & alternative_value) const;
/// Return the parameters by the given parameter names.
/**
* Like get_parameter(const std::string &), this method may throw the
* rclcpp::exceptions::ParameterNotDeclaredException exception if the
* requested parameter has not been declared and undeclared parameters are
* not allowed, and may throw the rclcpp::exceptions::ParameterUninitializedException exception.
*
* Also like get_parameter(const std::string &), if undeclared parameters are allowed and the
* parameter has not been declared, then the corresponding rclcpp::Parameter
* will be default initialized and therefore have the type
* rclcpp::ParameterType::PARAMETER_NOT_SET.
*
* \param[in] names The names of the parameters to be retrieved.
* \return The parameters that were retrieved.
* \throws rclcpp::exceptions::ParameterNotDeclaredException if any of the
* parameters have not been declared and undeclared parameters are not
* allowed.
* \throws rclcpp::exceptions::ParameterUninitializedException if any of the
* parameters have not been initialized.
*/
RCLCPP_PUBLIC
std::vector<rclcpp::Parameter>
get_parameters(const std::vector<std::string> & names) const;
/// Get the parameter values for all parameters that have a given prefix.
/**
* The "prefix" argument is used to list the parameters which are prefixed
* with that prefix, see also list_parameters().
*
* The resulting list of parameter names are used to get the values of the
* parameters.
*
* The names which are used as keys in the values map have the prefix removed.
* For example, if you use the prefix "foo" and the parameters "foo.ping" and
* "foo.pong" exist, then the returned map will have the keys "ping" and
* "pong".
*
* An empty string for the prefix will match all parameters.
*
* If no parameters with the prefix are found, then the output parameter
* "values" will be unchanged and false will be returned.
* Otherwise, the parameter names and values will be stored in the map and
* true will be returned to indicate "values" was mutated.
*
* This method will never throw the
* rclcpp::exceptions::ParameterNotDeclaredException exception because the
* action of listing the parameters is done atomically with getting the
* values, and therefore they are only listed if already declared and cannot
* be undeclared before being retrieved.
*
* Like the templated get_parameter() variant, this method will attempt to
* coerce the parameter values into the type requested by the given
* template argument, which may fail and throw an exception.
*
* \param[in] prefix The prefix of the parameters to get.
* \param[out] values The map used to store the parameter names and values,
* respectively, with one entry per parameter matching prefix.
* \returns true if output "values" was changed, false otherwise.
* \throws rclcpp::ParameterTypeException if the requested type does not
* match the value of the parameter which is stored.
*/
template<typename ParameterT>
bool
get_parameters(
const std::string & prefix,
std::map<std::string, ParameterT> & values) const;
/// Return the parameter descriptor for the given parameter name.
/**
* Like get_parameters(), this method may throw the
* rclcpp::exceptions::ParameterNotDeclaredException exception if the
* requested parameter has not been declared and undeclared parameters are
* not allowed.
*
* If undeclared parameters are allowed, then a default initialized
* descriptor will be returned.
*
* \param[in] name The name of the parameter to describe.
* \return The descriptor for the given parameter name.
* \throws rclcpp::exceptions::ParameterNotDeclaredException if the
* parameter has not been declared and undeclared parameters are not
* allowed.
* \throws std::runtime_error if the number of described parameters is more than one
*/
RCLCPP_PUBLIC
rcl_interfaces::msg::ParameterDescriptor
describe_parameter(const std::string & name) const;
/// Return a vector of parameter descriptors, one for each of the given names.
/**
* Like get_parameters(), this method may throw the
* rclcpp::exceptions::ParameterNotDeclaredException exception if any of the
* requested parameters have not been declared and undeclared parameters are
* not allowed.
*
* If undeclared parameters are allowed, then a default initialized
* descriptor will be returned for the undeclared parameter's descriptor.
*
* If the names vector is empty, then an empty vector will be returned.
*
* \param[in] names The list of parameter names to describe.
* \return A list of parameter descriptors, one for each parameter given.
* \throws rclcpp::exceptions::ParameterNotDeclaredException if any of the
* parameters have not been declared and undeclared parameters are not
* allowed.
* \throws std::runtime_error if the number of described parameters is more than one
*/
RCLCPP_PUBLIC
std::vector<rcl_interfaces::msg::ParameterDescriptor>
describe_parameters(const std::vector<std::string> & names) const;
/// Return a vector of parameter types, one for each of the given names.
/**
* Like get_parameters(), this method may throw the
* rclcpp::exceptions::ParameterNotDeclaredException exception if any of the
* requested parameters have not been declared and undeclared parameters are
* not allowed.
*
* If undeclared parameters are allowed, then the default type
* rclcpp::ParameterType::PARAMETER_NOT_SET will be returned.
*
* \param[in] names The list of parameter names to get the types.
* \return A list of parameter types, one for each parameter given.
* \throws rclcpp::exceptions::ParameterNotDeclaredException if any of the
* parameters have not been declared and undeclared parameters are not
* allowed.
*/
RCLCPP_PUBLIC
std::vector<uint8_t>
get_parameter_types(const std::vector<std::string> & names) const;
/// Return a list of parameters with any of the given prefixes, up to the given depth.
/**
* Parameters are separated into a hierarchy using the "." (dot) character.
* The "prefixes" argument is a way to select only particular parts of the hierarchy.
*
* \param[in] prefixes The list of prefixes that should be searched for within the
* current parameters. If this vector of prefixes is empty, then list_parameters
* will return all parameters.
* \param[in] depth An unsigned integer that represents the recursive depth to search.