-
Notifications
You must be signed in to change notification settings - Fork 243
/
Copy pathtest_node.py
2751 lines (2435 loc) · 116 KB
/
test_node.py
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 2017 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.
import pathlib
import platform
import time
from typing import List
import unittest
from unittest.mock import Mock
import warnings
import pytest
from rcl_interfaces.msg import FloatingPointRange
from rcl_interfaces.msg import IntegerRange
from rcl_interfaces.msg import ListParametersResult
from rcl_interfaces.msg import ParameterDescriptor
from rcl_interfaces.msg import ParameterType
from rcl_interfaces.msg import ParameterValue
from rcl_interfaces.msg import SetParametersResult
from rcl_interfaces.srv import GetParameters
import rclpy
from rclpy.clock_type import ClockType
from rclpy.duration import Duration
from rclpy.exceptions import InvalidParameterException
from rclpy.exceptions import InvalidParameterTypeException
from rclpy.exceptions import InvalidParameterValueException
from rclpy.exceptions import InvalidServiceNameException
from rclpy.exceptions import InvalidTopicNameException
from rclpy.exceptions import ParameterAlreadyDeclaredException
from rclpy.exceptions import ParameterImmutableException
from rclpy.exceptions import ParameterNotDeclaredException
from rclpy.exceptions import ParameterUninitializedException
from rclpy.executors import SingleThreadedExecutor
from rclpy.parameter import Parameter
from rclpy.qos import qos_profile_sensor_data
from rclpy.qos import QoSDurabilityPolicy
from rclpy.qos import QoSHistoryPolicy
from rclpy.qos import QoSLivelinessPolicy
from rclpy.qos import QoSProfile
from rclpy.qos import QoSReliabilityPolicy
from rclpy.time_source import USE_SIM_TIME_NAME
from rclpy.topic_endpoint_info import TopicEndpointTypeEnum
from rclpy.type_description_service import START_TYPE_DESCRIPTION_SERVICE_PARAM
from rclpy.utilities import get_rmw_implementation_identifier
from test_msgs.msg import BasicTypes
from test_msgs.srv import Empty
TEST_NODE = 'my_node'
TEST_NAMESPACE = '/my_ns'
TEST_RESOURCES_DIR = pathlib.Path(__file__).resolve().parent / 'resources' / 'test_node'
class TestNodeAllowUndeclaredParameters(unittest.TestCase):
@classmethod
def setUpClass(cls):
cls.context = rclpy.context.Context()
rclpy.init(context=cls.context)
@classmethod
def tearDownClass(cls):
rclpy.shutdown(context=cls.context)
def setUp(self):
self.node = rclpy.create_node(
TEST_NODE, namespace=TEST_NAMESPACE, context=self.context,
allow_undeclared_parameters=True)
def tearDown(self):
self.node.destroy_node()
def test_accessors(self):
self.assertIsNotNone(self.node.handle)
with self.assertRaises(AttributeError):
self.node.handle = 'garbage'
self.assertEqual(self.node.get_name(), TEST_NODE)
self.assertEqual(self.node.get_namespace(), TEST_NAMESPACE)
self.assertEqual(self.node.get_clock().clock_type, ClockType.ROS_TIME)
def test_create_publisher(self):
self.node.create_publisher(BasicTypes, 'chatter', 1)
self.node.create_publisher(BasicTypes, 'chatter', qos_profile_sensor_data)
with self.assertRaisesRegex(InvalidTopicNameException, 'must not contain characters'):
self.node.create_publisher(BasicTypes, 'chatter?', 1)
with self.assertRaisesRegex(InvalidTopicNameException, 'must not start with a number'):
self.node.create_publisher(BasicTypes, '/chatter/42_is_the_answer', 1)
with self.assertRaisesRegex(ValueError, 'unknown substitution'):
self.node.create_publisher(BasicTypes, 'chatter/{bad_sub}', 1)
with self.assertRaisesRegex(ValueError, 'must be greater than or equal to zero'):
self.node.create_publisher(BasicTypes, 'chatter', -1)
with self.assertRaisesRegex(TypeError, 'Expected QoSProfile or int'):
self.node.create_publisher(BasicTypes, 'chatter', 'foo')
def test_create_subscription(self):
self.node.create_subscription(BasicTypes, 'chatter', lambda msg: print(msg), 1)
self.node.create_subscription(
BasicTypes, 'chatter', lambda msg: print(msg), qos_profile_sensor_data)
with self.assertRaisesRegex(InvalidTopicNameException, 'must not contain characters'):
self.node.create_subscription(BasicTypes, 'chatter?', lambda msg: print(msg), 1)
with self.assertRaisesRegex(InvalidTopicNameException, 'must not start with a number'):
self.node.create_subscription(BasicTypes, '/chatter/42ish', lambda msg: print(msg), 1)
with self.assertRaisesRegex(ValueError, 'unknown substitution'):
self.node.create_subscription(BasicTypes, 'foo/{bad_sub}', lambda msg: print(msg), 1)
with self.assertRaisesRegex(ValueError, 'must be greater than or equal to zero'):
self.node.create_subscription(BasicTypes, 'chatter', lambda msg: print(msg), -1)
with self.assertRaisesRegex(TypeError, 'Expected QoSProfile or int'):
self.node.create_subscription(BasicTypes, 'chatter', lambda msg: print(msg), 'foo')
def raw_subscription_callback(self, msg):
print('Raw subscription callback: %s length %d' % (msg, len(msg)))
self.raw_subscription_msg = msg
def test_create_raw_subscription(self):
executor = SingleThreadedExecutor(context=self.context)
executor.add_node(self.node)
basic_types_pub = self.node.create_publisher(BasicTypes, 'raw_subscription_test', 1)
self.raw_subscription_msg = None # None=No result yet
self.node.create_subscription(
BasicTypes,
'raw_subscription_test',
self.raw_subscription_callback,
1,
raw=True
)
basic_types_msg = BasicTypes()
cycle_count = 0
while cycle_count < 5 and self.raw_subscription_msg is None:
basic_types_pub.publish(basic_types_msg)
cycle_count += 1
executor.spin_once(timeout_sec=1)
self.assertIsNotNone(self.raw_subscription_msg, 'raw subscribe timed out')
self.assertIs(type(self.raw_subscription_msg), bytes, 'raw subscribe did not return bytes')
# The length might be implementation dependant, but shouldn't be zero
# There may be a canonical serialization in the future at which point this can be updated
self.assertNotEqual(len(self.raw_subscription_msg), 0, 'raw subscribe invalid length')
executor.shutdown()
def dummy_cb(self, msg):
pass
@unittest.skipIf(
get_rmw_implementation_identifier() == 'rmw_connextdds' and platform.system() == 'Windows',
reason='Source timestamp not implemented for Connext on Windows')
def test_take(self):
basic_types_pub = self.node.create_publisher(BasicTypes, 'take_test', 1)
sub = self.node.create_subscription(
BasicTypes,
'take_test',
self.dummy_cb,
1)
basic_types_msg = BasicTypes()
basic_types_pub.publish(basic_types_msg)
for i in range(5):
with sub.handle:
result = sub.handle.take_message(sub.msg_type, False)
if result is not None:
msg, info = result
self.assertNotEqual(0, info['source_timestamp'])
return
else:
time.sleep(0.2)
def test_create_client(self):
self.node.create_client(GetParameters, 'get/parameters')
with self.assertRaisesRegex(InvalidServiceNameException, 'must not contain characters'):
self.node.create_client(GetParameters, 'get/parameters?')
with self.assertRaisesRegex(InvalidServiceNameException, 'must not start with a number'):
self.node.create_client(GetParameters, '/get/42parameters')
with self.assertRaisesRegex(ValueError, 'unknown substitution'):
self.node.create_client(GetParameters, 'foo/{bad_sub}')
def test_create_service(self):
self.node.create_service(GetParameters, 'get/parameters', lambda req: None)
with self.assertRaisesRegex(InvalidServiceNameException, 'must not contain characters'):
self.node.create_service(GetParameters, 'get/parameters?', lambda req: None)
with self.assertRaisesRegex(InvalidServiceNameException, 'must not start with a number'):
self.node.create_service(GetParameters, '/get/42parameters', lambda req: None)
with self.assertRaisesRegex(ValueError, 'unknown substitution'):
self.node.create_service(GetParameters, 'foo/{bad_sub}', lambda req: None)
def test_service_names_and_types(self):
# test that it doesn't raise
self.node.get_service_names_and_types()
def test_service_names_and_types_by_node(self):
# test that it doesn't raise
self.node.get_service_names_and_types_by_node(TEST_NODE, TEST_NAMESPACE)
def test_client_names_and_types_by_node(self):
# test that it doesn't raise
self.node.get_client_names_and_types_by_node(TEST_NODE, TEST_NAMESPACE)
def test_topic_names_and_types(self):
# test that it doesn't raise
self.node.get_topic_names_and_types(no_demangle=True)
self.node.get_topic_names_and_types(no_demangle=False)
def test_node_names(self):
# test that it doesn't raise
self.node.get_node_names()
def test_node_names_and_namespaces(self):
# test that it doesn't raise
self.node.get_node_names_and_namespaces()
def test_node_names_and_namespaces_with_enclaves(self):
# test that it doesn't raise
self.node.get_node_names_and_namespaces_with_enclaves()
def assert_qos_equal(self, expected_qos_profile, actual_qos_profile, *, is_publisher):
# Depth and history are skipped because they are not retrieved.
self.assertEqual(
expected_qos_profile.durability,
actual_qos_profile.durability,
'Durability is unequal')
self.assertEqual(
expected_qos_profile.reliability,
actual_qos_profile.reliability,
'Reliability is unequal')
if is_publisher:
self.assertEqual(
expected_qos_profile.lifespan,
actual_qos_profile.lifespan,
'lifespan is unequal')
self.assertEqual(
expected_qos_profile.deadline,
actual_qos_profile.deadline,
'Deadline is unequal')
self.assertEqual(
expected_qos_profile.liveliness,
actual_qos_profile.liveliness,
'liveliness is unequal')
self.assertEqual(
expected_qos_profile.liveliness_lease_duration,
actual_qos_profile.liveliness_lease_duration,
'liveliness_lease_duration is unequal')
def test_get_publishers_subscriptions_info_by_topic(self):
topic_name = 'test_topic_endpoint_info'
fq_topic_name = '{namespace}/{name}'.format(namespace=TEST_NAMESPACE, name=topic_name)
# Lists should be empty
self.assertFalse(self.node.get_publishers_info_by_topic(fq_topic_name))
self.assertFalse(self.node.get_subscriptions_info_by_topic(fq_topic_name))
# Add a publisher
qos_profile = QoSProfile(
depth=10,
history=QoSHistoryPolicy.KEEP_ALL,
deadline=Duration(seconds=1, nanoseconds=12345),
lifespan=Duration(seconds=20, nanoseconds=9887665),
reliability=QoSReliabilityPolicy.BEST_EFFORT,
durability=QoSDurabilityPolicy.TRANSIENT_LOCAL,
liveliness_lease_duration=Duration(seconds=5, nanoseconds=23456),
liveliness=QoSLivelinessPolicy.MANUAL_BY_TOPIC)
self.node.create_publisher(BasicTypes, topic_name, qos_profile)
# List should have one item
publisher_list = self.node.get_publishers_info_by_topic(fq_topic_name)
self.assertEqual(1, len(publisher_list))
# Subscription list should be empty
self.assertFalse(self.node.get_subscriptions_info_by_topic(fq_topic_name))
# Verify publisher list has the right data
self.assertEqual(self.node.get_name(), publisher_list[0].node_name)
self.assertEqual(self.node.get_namespace(), publisher_list[0].node_namespace)
self.assertEqual('test_msgs/msg/BasicTypes', publisher_list[0].topic_type)
actual_qos_profile = publisher_list[0].qos_profile
self.assert_qos_equal(qos_profile, actual_qos_profile, is_publisher=True)
# Add a subscription
qos_profile2 = QoSProfile(
depth=1,
history=QoSHistoryPolicy.KEEP_LAST,
deadline=Duration(seconds=15, nanoseconds=1678),
lifespan=Duration(seconds=29, nanoseconds=2345),
reliability=QoSReliabilityPolicy.RELIABLE,
durability=QoSDurabilityPolicy.VOLATILE,
liveliness_lease_duration=Duration(seconds=5, nanoseconds=23456),
liveliness=QoSLivelinessPolicy.AUTOMATIC)
self.node.create_subscription(BasicTypes, topic_name, lambda msg: print(msg), qos_profile2)
# Both lists should have one item
publisher_list = self.node.get_publishers_info_by_topic(fq_topic_name)
subscription_list = self.node.get_subscriptions_info_by_topic(fq_topic_name)
self.assertEqual(1, len(publisher_list))
self.assertEqual(1, len(subscription_list))
# Verify subscription list has the right data
self.assertEqual(self.node.get_name(), publisher_list[0].node_name)
self.assertEqual(self.node.get_namespace(), publisher_list[0].node_namespace)
self.assertEqual('test_msgs/msg/BasicTypes', publisher_list[0].topic_type)
self.assertEqual('test_msgs/msg/BasicTypes', subscription_list[0].topic_type)
publisher_qos_profile = publisher_list[0].qos_profile
subscription_qos_profile = subscription_list[0].qos_profile
self.assert_qos_equal(qos_profile, publisher_qos_profile, is_publisher=True)
self.assert_qos_equal(qos_profile2, subscription_qos_profile, is_publisher=False)
# Error cases
with self.assertRaises(TypeError):
self.node.get_subscriptions_info_by_topic(1)
self.node.get_publishers_info_by_topic(1)
with self.assertRaisesRegex(ValueError, 'is invalid'):
self.node.get_subscriptions_info_by_topic('13')
self.node.get_publishers_info_by_topic('13')
def test_get_clients_servers_info_by_service(self):
service_name = 'test_service_endpoint_info'
fq_service_name = '{namespace}/{name}'.format(namespace=TEST_NAMESPACE, name=service_name)
# Lists should be empty
self.assertFalse(self.node.get_clients_info_by_service(fq_service_name))
self.assertFalse(self.node.get_servers_info_by_service(fq_service_name))
# Add a client
qos_profile = QoSProfile(
depth=10,
history=QoSHistoryPolicy.KEEP_ALL,
deadline=Duration(seconds=1, nanoseconds=12345),
lifespan=Duration(seconds=20, nanoseconds=9887665),
reliability=QoSReliabilityPolicy.BEST_EFFORT,
durability=QoSDurabilityPolicy.TRANSIENT_LOCAL,
liveliness_lease_duration=Duration(seconds=5, nanoseconds=23456),
liveliness=QoSLivelinessPolicy.MANUAL_BY_TOPIC)
self.node.create_client(Empty, service_name, qos_profile=qos_profile)
# List should have at least one item
client_list = self.node.get_clients_info_by_service(fq_service_name)
self.assertGreaterEqual(len(client_list), 1)
# Server list should be empty
self.assertFalse(self.node.get_servers_info_by_service(fq_service_name))
# Verify client list has the right data
for client in client_list:
self.assertEqual(self.node.get_name(), client.node_name)
self.assertEqual(self.node.get_namespace(), client.node_namespace)
assert 'test_msgs/srv/Empty' in client.topic_type
if 'test_msgs/srv/Empty_Request' == client.topic_type:
actual_qos_profile = client.qos_profile
assert client.endpoint_type == TopicEndpointTypeEnum.PUBLISHER
self.assert_qos_equal(qos_profile, actual_qos_profile, is_publisher=True)
elif 'test_msgs/srv/Empty_Response' == client.topic_type:
actual_qos_profile = client.qos_profile
assert client.endpoint_type == TopicEndpointTypeEnum.SUBSCRIPTION
self.assert_qos_equal(qos_profile, actual_qos_profile, is_publisher=False)
# Add a server
qos_profile2 = QoSProfile(
depth=1,
history=QoSHistoryPolicy.KEEP_LAST,
deadline=Duration(seconds=15, nanoseconds=1678),
lifespan=Duration(seconds=29, nanoseconds=2345),
reliability=QoSReliabilityPolicy.RELIABLE,
durability=QoSDurabilityPolicy.VOLATILE,
liveliness_lease_duration=Duration(seconds=5, nanoseconds=23456),
liveliness=QoSLivelinessPolicy.AUTOMATIC)
self.node.create_service(
Empty,
service_name,
lambda msg: print(msg),
qos_profile=qos_profile2
)
# Both lists should have at least one item
client_list = self.node.get_clients_info_by_service(fq_service_name)
server_list = self.node.get_servers_info_by_service(fq_service_name)
self.assertGreaterEqual(len(client_list), 1)
self.assertGreaterEqual(len(server_list), 1)
# Verify server list has the right data
for server in server_list:
self.assertEqual(self.node.get_name(), server.node_name)
self.assertEqual(self.node.get_namespace(), server.node_namespace)
assert 'test_msgs/srv/Empty' in server.topic_type
if 'test_msgs/srv/Empty_Request' == server.topic_type:
actual_qos_profile = server.qos_profile
assert server.endpoint_type == TopicEndpointTypeEnum.SUBSCRIPTION
self.assert_qos_equal(qos_profile2, actual_qos_profile, is_publisher=False)
elif 'test_msgs/srv/Empty_Response' == server.topic_type:
actual_qos_profile = server.qos_profile
assert server.endpoint_type == TopicEndpointTypeEnum.PUBLISHER
self.assert_qos_equal(qos_profile2, actual_qos_profile, is_publisher=True)
# Error cases
with self.assertRaises(TypeError):
self.node.get_clients_info_by_service(1)
self.node.get_servers_info_by_service(1)
with self.assertRaisesRegex(ValueError, 'is invalid'):
self.node.get_clients_info_by_service('13')
self.node.get_servers_info_by_service('13')
def test_count_publishers_subscribers(self):
short_topic_name = 'chatter'
fq_topic_name = '%s/%s' % (TEST_NAMESPACE, short_topic_name)
self.assertEqual(0, self.node.count_publishers(fq_topic_name))
self.assertEqual(0, self.node.count_subscribers(fq_topic_name))
short_topic_publisher = self.node.create_publisher(BasicTypes, short_topic_name, 1)
self.assertEqual(1, self.node.count_publishers(short_topic_name))
self.assertEqual(1, self.node.count_publishers(fq_topic_name))
self.assertEqual(0, short_topic_publisher.get_subscription_count())
self.node.create_subscription(BasicTypes, short_topic_name, lambda msg: print(msg), 1)
self.assertEqual(1, self.node.count_subscribers(short_topic_name))
self.assertEqual(1, self.node.count_subscribers(fq_topic_name))
self.assertEqual(1, short_topic_publisher.get_subscription_count())
self.node.create_subscription(BasicTypes, short_topic_name, lambda msg: print(msg), 1)
self.assertEqual(2, self.node.count_subscribers(short_topic_name))
self.assertEqual(2, self.node.count_subscribers(fq_topic_name))
self.assertEqual(2, short_topic_publisher.get_subscription_count())
# error cases
with self.assertRaises(TypeError):
self.node.count_subscribers(1)
with self.assertRaisesRegex(ValueError, 'is invalid'):
self.node.count_subscribers('42')
with self.assertRaisesRegex(ValueError, 'is invalid'):
self.node.count_publishers('42')
def test_count_clients_services(self):
short_service_name = 'add_two_ints'
fq_service_name = '%s/%s' % (TEST_NAMESPACE, short_service_name)
self.assertEqual(0, self.node.count_clients(fq_service_name))
self.assertEqual(0, self.node.count_services(fq_service_name))
self.node.create_client(GetParameters, short_service_name)
self.assertEqual(1, self.node.count_clients(short_service_name))
self.assertEqual(1, self.node.count_clients(fq_service_name))
self.assertEqual(0, self.node.count_services(short_service_name))
self.assertEqual(0, self.node.count_services(fq_service_name))
self.node.create_service(GetParameters, short_service_name, lambda req: None)
self.assertEqual(1, self.node.count_clients(short_service_name))
self.assertEqual(1, self.node.count_clients(fq_service_name))
self.assertEqual(1, self.node.count_services(short_service_name))
self.assertEqual(1, self.node.count_services(fq_service_name))
self.node.create_client(GetParameters, short_service_name)
self.assertEqual(2, self.node.count_clients(short_service_name))
self.assertEqual(2, self.node.count_clients(fq_service_name))
self.assertEqual(1, self.node.count_services(short_service_name))
self.assertEqual(1, self.node.count_services(fq_service_name))
self.node.create_service(GetParameters, short_service_name, lambda req: None)
self.assertEqual(2, self.node.count_clients(short_service_name))
self.assertEqual(2, self.node.count_clients(fq_service_name))
self.assertEqual(2, self.node.count_services(short_service_name))
self.assertEqual(2, self.node.count_services(fq_service_name))
# error cases
with self.assertRaises(TypeError):
self.node.count_clients(1)
with self.assertRaises(TypeError):
self.node.count_services(1)
with self.assertRaisesRegex(ValueError, 'is invalid'):
self.node.count_clients('42')
with self.assertRaisesRegex(ValueError, 'is invalid'):
self.node.count_services('42')
def test_node_logger(self):
node_logger = self.node.get_logger()
expected_name = '%s.%s' % (TEST_NAMESPACE.replace('/', '.')[1:], TEST_NODE)
self.assertEqual(node_logger.name, expected_name)
node_logger.set_level(rclpy.logging.LoggingSeverity.INFO)
node_logger.debug('test')
def modify_parameter_callback(self, parameters_list: List[Parameter]):
modified_list = parameters_list.copy()
for param in parameters_list:
if param.name == 'foo':
modified_list.append(Parameter('bar', Parameter.Type.STRING, 'hello'))
return modified_list
def test_node_set_parameters(self):
results = self.node.set_parameters([
Parameter('foo', Parameter.Type.INTEGER, 42),
Parameter('bar', Parameter.Type.STRING, 'hello'),
Parameter('baz', Parameter.Type.DOUBLE, 2.41)
])
self.assertTrue(all(isinstance(result, SetParametersResult) for result in results))
self.assertTrue(all(result.successful for result in results))
self.assertEqual(self.node.get_parameter('foo').value, 42)
self.assertEqual(self.node.get_parameter('bar').value, 'hello')
self.assertEqual(self.node.get_parameter('baz').value, 2.41)
self.node.undeclare_parameter('foo')
self.node.undeclare_parameter('bar')
self.node.undeclare_parameter('baz')
# adding a parameter using func: "add_pre_set parameter" callback when
# that parameter has not been declared will not throw if undeclared
# parameters are allowed
self.node.add_pre_set_parameters_callback(self.modify_parameter_callback)
results = self.node.set_parameters([
Parameter('foo', Parameter.Type.INTEGER, 42),
Parameter('baz', Parameter.Type.DOUBLE, 2.41)
])
self.node.remove_pre_set_parameters_callback(self.modify_parameter_callback)
self.assertEqual(2, len(results))
self.assertTrue(all(isinstance(result, SetParametersResult) for result in results))
self.assertTrue(all(result.successful for result in results))
self.assertTrue(self.node.has_parameter('foo'))
self.assertTrue(self.node.has_parameter('bar'))
self.assertTrue(self.node.has_parameter('baz'))
self.assertEqual(self.node.get_parameter('foo').value, 42)
self.assertEqual(self.node.get_parameter('bar').value, 'hello')
self.assertEqual(self.node.get_parameter('baz').value, 2.41)
def test_node_cannot_set_invalid_parameters(self):
with self.assertRaises(TypeError):
self.node.set_parameters([42])
def test_node_set_parameters_atomically(self):
result = self.node.set_parameters_atomically([
Parameter('foo', Parameter.Type.INTEGER, 42),
Parameter('bar', Parameter.Type.STRING, 'hello'),
Parameter('baz', Parameter.Type.DOUBLE, 2.41)
])
self.assertEqual(self.node.get_parameter('foo').value, 42)
self.assertIsInstance(result, SetParametersResult)
self.assertTrue(result.successful)
self.node.undeclare_parameter('foo')
self.node.undeclare_parameter('bar')
self.node.undeclare_parameter('baz')
# adding a parameter using func: "add_pre_set parameter" callback,
# when that parameter has not been declared will not throw if undeclared
# parameters are allowed
self.node.add_pre_set_parameters_callback(self.modify_parameter_callback)
result = self.node.set_parameters_atomically([
Parameter('foo', Parameter.Type.INTEGER, 42),
Parameter('baz', Parameter.Type.DOUBLE, 2.41)
])
self.node.remove_pre_set_parameters_callback(self.modify_parameter_callback)
self.assertEqual(True, result.successful)
self.assertTrue(self.node.has_parameter('foo'))
self.assertTrue(self.node.has_parameter('bar'))
self.assertTrue(self.node.has_parameter('baz'))
self.assertEqual(self.node.get_parameter('foo').value, 42)
self.assertEqual(self.node.get_parameter('bar').value, 'hello')
self.assertEqual(self.node.get_parameter('baz').value, 2.41)
def test_describe_undeclared_parameter(self):
self.assertFalse(self.node.has_parameter('foo'))
descriptor = self.node.describe_parameter('foo')
self.assertEqual(descriptor, ParameterDescriptor())
def test_describe_undeclared_parameters(self):
self.assertFalse(self.node.has_parameter('foo'))
self.assertFalse(self.node.has_parameter('bar'))
# Check list.
descriptor_list = self.node.describe_parameters(['foo', 'bar'])
self.assertIsInstance(descriptor_list, list)
self.assertEqual(len(descriptor_list), 2)
self.assertEqual(descriptor_list[0], ParameterDescriptor())
self.assertEqual(descriptor_list[1], ParameterDescriptor())
def test_node_get_parameter(self):
self.node.set_parameters([Parameter('foo', Parameter.Type.INTEGER, 42)])
self.assertIsInstance(self.node.get_parameter('foo'), Parameter)
self.assertEqual(self.node.get_parameter('foo').value, 42)
def test_node_get_parameter_returns_parameter_not_set(self):
self.assertIsInstance(self.node.get_parameter('unset'), Parameter)
self.assertEqual(self.node.get_parameter('unset').type_, Parameter.Type.NOT_SET)
def test_node_declare_static_parameter(self):
value = self.node.declare_parameter('an_integer', 5)
self.assertEqual(value.value, 5)
self.assertFalse(
self.node.set_parameters([Parameter('an_integer', value='asd')])[0].successful)
self.assertEqual(self.node.get_parameter('an_integer').value, 5)
def test_node_undeclared_parameters_are_dynamically_typed(self):
self.assertTrue(self.node.set_parameters([Parameter('my_param', value=5)])[0].successful)
self.assertEqual(self.node.get_parameter('my_param').value, 5)
self.assertTrue(
self.node.set_parameters([Parameter('my_param', value='asd')])[0].successful)
self.assertEqual(self.node.get_parameter('my_param').value, 'asd')
def test_node_cannot_declare_after_set(self):
self.assertTrue(self.node.set_parameters([Parameter('my_param', value=5)])[0].successful)
self.assertEqual(self.node.get_parameter('my_param').value, 5)
with pytest.raises(rclpy.exceptions.ParameterAlreadyDeclaredException):
self.node.declare_parameter('my_param', 5)
def test_node_has_parameter_services(self):
service_names_and_types = self.node.get_service_names_and_types()
self.assertIn(
('/my_ns/my_node/describe_parameters', ['rcl_interfaces/srv/DescribeParameters']),
service_names_and_types
)
self.assertIn(
('/my_ns/my_node/get_parameter_types', ['rcl_interfaces/srv/GetParameterTypes']),
service_names_and_types
)
self.assertIn(
('/my_ns/my_node/get_parameters', ['rcl_interfaces/srv/GetParameters']),
service_names_and_types
)
self.assertIn(
('/my_ns/my_node/list_parameters', ['rcl_interfaces/srv/ListParameters']),
service_names_and_types
)
self.assertIn(
('/my_ns/my_node/set_parameters', ['rcl_interfaces/srv/SetParameters']),
service_names_and_types
)
self.assertIn(
(
'/my_ns/my_node/set_parameters_atomically',
['rcl_interfaces/srv/SetParametersAtomically']
), service_names_and_types
)
class TestExecutor(unittest.TestCase):
@classmethod
def setUpClass(cls):
cls.context = rclpy.context.Context()
rclpy.init(context=cls.context)
@classmethod
def tearDownClass(cls):
rclpy.shutdown(context=cls.context)
def setUp(self):
self.node = rclpy.create_node(TEST_NODE, context=self.context)
def tearDown(self):
self.node.destroy_node()
def test_initially_no_executor(self):
assert self.node.executor is None
def test_set_executor_adds_node_to_it(self):
executor = Mock()
executor.add_node.return_value = True
self.node.executor = executor
assert id(executor) == id(self.node.executor)
executor.add_node.assert_called_once_with(self.node)
def test_set_executor_removes_node_from_old_executor(self):
old_executor = Mock()
old_executor.add_node.return_value = True
new_executor = Mock()
new_executor.add_node.return_value = True
self.node.executor = old_executor
assert id(old_executor) == id(self.node.executor)
self.node.executor = new_executor
assert id(new_executor) == id(self.node.executor)
old_executor.remove_node.assert_called_once_with(self.node)
new_executor.remove_node.assert_not_called()
def test_set_executor_clear_executor(self):
executor = Mock()
executor.add_node.return_value = True
self.node.executor = executor
assert id(executor) == id(self.node.executor)
self.node.executor = None
assert self.node.executor is None
class TestNode(unittest.TestCase):
@classmethod
def setUpClass(cls):
cls.context = rclpy.context.Context()
rclpy.init(context=cls.context)
@classmethod
def tearDownClass(cls):
rclpy.shutdown(context=cls.context)
def setUp(self):
self.node = rclpy.create_node(
TEST_NODE,
namespace=TEST_NAMESPACE,
context=self.context,
parameter_overrides=[
Parameter('initial_foo', Parameter.Type.INTEGER, 4321),
Parameter('initial_bar', Parameter.Type.STRING, 'init_param'),
Parameter('initial_baz', Parameter.Type.DOUBLE, 3.14),
Parameter('initial_decl_with_type', Parameter.Type.DOUBLE, 3.14),
Parameter('initial_decl_wrong_type', Parameter.Type.DOUBLE, 3.14),
Parameter('namespace.k_initial_foo', Parameter.Type.INTEGER, 4321),
Parameter('namespace.k_initial_bar', Parameter.Type.STRING, 'init_param'),
Parameter('namespace.k_initial_baz', Parameter.Type.DOUBLE, 3.14),
Parameter('namespace.k_initial_decl_with_type', Parameter.Type.DOUBLE, 3.14),
Parameter('namespace.k_initial_decl_wrong_type', Parameter.Type.DOUBLE, 3.14),
Parameter('namespace.k_initial_foo', Parameter.Type.INTEGER, 4321)
],
cli_args=[
'--ros-args', '-p', 'initial_fizz:=buzz',
'--params-file', str(TEST_RESOURCES_DIR / 'test_parameters.yaml'),
'-p', 'initial_buzz:=1.'
],
automatically_declare_parameters_from_overrides=False
)
def tearDown(self):
self.node.destroy_node()
def test_declare_parameter(self):
with pytest.raises(ValueError):
result_initial_foo = self.node.declare_parameter(
'initial_foo', ParameterValue(), ParameterDescriptor())
result_initial_foo = self.node.declare_parameter(
'initial_foo', ParameterValue(), ParameterDescriptor(dynamic_typing=True))
result_initial_bar = self.node.declare_parameter(
'initial_bar', 'ignoring_override', ParameterDescriptor(), ignore_override=True)
result_initial_fizz = self.node.declare_parameter(
'initial_fizz', 'default', ParameterDescriptor())
result_initial_baz = self.node.declare_parameter(
'initial_baz', 0., ParameterDescriptor())
result_initial_buzz = self.node.declare_parameter(
'initial_buzz', 0., ParameterDescriptor())
result_initial_foobar = self.node.declare_parameter(
'initial_foobar', True, ParameterDescriptor())
result_foo = self.node.declare_parameter(
'foo', 42, ParameterDescriptor())
result_bar = self.node.declare_parameter(
'bar', 'hello', ParameterDescriptor())
result_baz = self.node.declare_parameter(
'baz', 2.41, ParameterDescriptor())
with warnings.catch_warnings(record=True) as w:
warnings.simplefilter('always', category=UserWarning)
result_value_not_set = self.node.declare_parameter('value_not_set')
assert len(w) == 1
assert issubclass(w[0].category, UserWarning)
# OK cases.
self.assertIsInstance(result_initial_foo, Parameter)
self.assertIsInstance(result_initial_bar, Parameter)
self.assertIsInstance(result_initial_fizz, Parameter)
self.assertIsInstance(result_initial_baz, Parameter)
self.assertIsInstance(result_foo, Parameter)
self.assertIsInstance(result_bar, Parameter)
self.assertIsInstance(result_baz, Parameter)
self.assertIsInstance(result_value_not_set, Parameter)
# initial_foo and initial_fizz get override values; initial_bar does not.
self.assertEqual(result_initial_foo.value, 4321)
self.assertEqual(result_initial_bar.value, 'ignoring_override')
# provided by CLI, overridden by file
self.assertEqual(result_initial_fizz.value, 'param_file_override')
self.assertEqual(result_initial_baz.value, 3.14) # provided by file, overridden manually
self.assertEqual(result_initial_buzz.value, 1.) # provided by CLI
self.assertEqual(result_initial_foobar.value, False) # provided by file
self.assertEqual(result_foo.value, 42)
self.assertEqual(result_bar.value, 'hello')
self.assertEqual(result_baz.value, 2.41)
self.assertIsNone(result_value_not_set.value)
self.assertEqual(self.node.get_parameter('initial_foo').value, 4321)
self.assertEqual(self.node.get_parameter('initial_bar').value, 'ignoring_override')
self.assertEqual(self.node.get_parameter('initial_fizz').value, 'param_file_override')
self.assertEqual(self.node.get_parameter('initial_baz').value, 3.14)
self.assertEqual(self.node.get_parameter('initial_buzz').value, 1)
self.assertEqual(self.node.get_parameter('initial_foobar').value, False)
self.assertEqual(self.node.get_parameter('foo').value, 42)
self.assertEqual(self.node.get_parameter('bar').value, 'hello')
self.assertEqual(self.node.get_parameter('baz').value, 2.41)
self.assertIsNone(self.node.get_parameter('value_not_set').value)
self.assertTrue(self.node.has_parameter('value_not_set'))
# Error cases.
# TODO(@jubeira): add failing test cases with invalid names once name
# validation is implemented.
with self.assertRaises(ParameterAlreadyDeclaredException):
self.node.declare_parameter(
'foo', 'raise', ParameterDescriptor())
with self.assertRaises(InvalidParameterException):
self.node.declare_parameter(
'', 'raise', ParameterDescriptor())
with self.assertRaises(InvalidParameterException):
self.node.declare_parameter(
'', 'raise', ParameterDescriptor())
self.node.add_on_set_parameters_callback(self.reject_parameter_callback)
with self.assertRaises(InvalidParameterValueException):
self.node.declare_parameter(
'reject_me', 'raise', ParameterDescriptor())
with self.assertRaises(TypeError):
self.node.declare_parameter(
1,
'wrong_name_type',
ParameterDescriptor())
with self.assertRaises(ValueError):
self.node.declare_parameter(
'wrong_parameter_value_type', ParameterValue(), ParameterDescriptor())
with self.assertRaises(TypeError):
self.node.declare_parameter(
'wrong_parameter_descriptor_type', 1, ParameterValue())
with self.assertRaises(ValueError):
self.node.declare_parameter(
'static_typing_wo_default_value',
descriptor=ParameterDescriptor(type=ParameterType.PARAMETER_NOT_SET))
with self.assertRaises(ValueError):
self.node.declare_parameter(
'static_typing_wo_default_value',
descriptor=ParameterDescriptor(type=ParameterType.PARAMETER_STRING))
with self.assertRaises(ValueError):
self.node.declare_parameter(
'dynamic_typing_and_static_type',
Parameter.Type.DOUBLE,
descriptor=ParameterDescriptor(dynamic_typing=True))
def test_declare_parameters(self):
parameters = [
('initial_foo', 0, ParameterDescriptor()),
('foo', 42, ParameterDescriptor()),
('bar', 'hello', ParameterDescriptor()),
('baz', 2.41),
('value_not_set',)
]
# Declare uninitialized parameter
parameter_type = self.node.declare_parameter('no_override', Parameter.Type.INTEGER).type_
assert parameter_type == Parameter.Type.NOT_SET
with pytest.raises(InvalidParameterTypeException):
self.node.declare_parameter('initial_decl_wrong_type', Parameter.Type.INTEGER)
self.assertAlmostEqual(
self.node.declare_parameter('initial_decl_with_type', Parameter.Type.DOUBLE).value,
3.14)
with warnings.catch_warnings(record=True) as w:
warnings.simplefilter('always', category=UserWarning)
result = self.node.declare_parameters('', parameters)
assert len(w) == 1
assert issubclass(w[0].category, UserWarning)
# OK cases - using overrides.
self.assertIsInstance(result, list)
self.assertEqual(len(result), len(parameters))
self.assertIsInstance(result[0], Parameter)
self.assertIsInstance(result[1], Parameter)
self.assertIsInstance(result[2], Parameter)
self.assertIsInstance(result[3], Parameter)
self.assertIsInstance(result[4], Parameter)
self.assertEqual(result[0].value, 4321)
self.assertEqual(result[1].value, 42)
self.assertEqual(result[2].value, 'hello')
self.assertEqual(result[3].value, 2.41)
self.assertIsNone(result[4].value)
self.assertEqual(self.node.get_parameter('initial_foo').value, 4321)
self.assertEqual(self.node.get_parameter('foo').value, 42)
self.assertEqual(self.node.get_parameter('bar').value, 'hello')
self.assertEqual(self.node.get_parameter('baz').value, 2.41)
self.assertIsNone(self.node.get_parameter('value_not_set').value)
self.assertTrue(self.node.has_parameter('value_not_set'))
parameters = [
('k_initial_foo', 0, ParameterDescriptor()),
('k_foo', 42, ParameterDescriptor()),
('k_bar', 'hello', ParameterDescriptor()),
('k_baz', 2.41),
('k_value_not_set',)
]
with warnings.catch_warnings(record=True) as w:
warnings.simplefilter('always', category=UserWarning)
result = self.node.declare_parameters('namespace', parameters)
assert len(w) == 1
# OK cases.
self.assertIsInstance(result, list)
self.assertEqual(len(result), len(parameters))
self.assertIsInstance(result[0], Parameter)
self.assertIsInstance(result[1], Parameter)
self.assertIsInstance(result[2], Parameter)
self.assertIsInstance(result[3], Parameter)
self.assertIsInstance(result[4], Parameter)
self.assertEqual(result[0].value, 4321)
self.assertEqual(result[1].value, 42)
self.assertEqual(result[2].value, 'hello')
self.assertEqual(result[3].value, 2.41)
self.assertIsNone(result[4].value)
self.assertEqual(self.node.get_parameter('namespace.k_initial_foo').value, 4321)
self.assertEqual(self.node.get_parameter('namespace.k_foo').value, 42)
self.assertEqual(self.node.get_parameter('namespace.k_bar').value, 'hello')
self.assertEqual(self.node.get_parameter('namespace.k_baz').value, 2.41)
self.assertIsNone(self.node.get_parameter('namespace.k_value_not_set').value)
self.assertTrue(self.node.has_parameter('namespace.k_value_not_set'))
parameters = [
('initial_bar', 'ignoring_override', ParameterDescriptor()),
('initial_baz', 'ignoring_override_again', ParameterDescriptor()),
]
result = self.node.declare_parameters('', parameters, ignore_override=True)
# OK cases - ignoring overrides.
self.assertIsInstance(result, list)
self.assertEqual(len(result), len(parameters))
self.assertIsInstance(result[0], Parameter)
self.assertIsInstance(result[1], Parameter)
self.assertEqual(result[0].value, 'ignoring_override')
self.assertEqual(result[1].value, 'ignoring_override_again')
self.assertEqual(self.node.get_parameter('initial_bar').value, 'ignoring_override')
self.assertEqual(self.node.get_parameter('initial_baz').value, 'ignoring_override_again')
# Error cases.
with self.assertRaises(ParameterAlreadyDeclaredException):
self.node.declare_parameters('', parameters)
# Declare a new set of parameters; the first one is not already declared,
# but 2nd and 3rd one are.
parameters = [
('foobar', 43, ParameterDescriptor()),
('bar', 'hello', ParameterDescriptor()),
('baz', 2.41, ParameterDescriptor()),
]
with self.assertRaises(ParameterAlreadyDeclaredException):
self.node.declare_parameters('', parameters)
# Declare a new set; the third one shall fail because of its name.
parameters = [
('foobarbar', 44, ParameterDescriptor()),
('barbarbar', 'world', ParameterDescriptor()),
('', 2.41, ParameterDescriptor()),
]
with self.assertRaises(InvalidParameterException):
self.node.declare_parameters('', parameters)
# Declare a new set; the third one shall be rejected by the callback.
parameters = [
('im_ok', 44, ParameterDescriptor()),
('im_also_ok', 'world', ParameterDescriptor()),
('reject_me', 2.41, ParameterDescriptor()),
]
self.node.add_on_set_parameters_callback(self.reject_parameter_callback)
with self.assertRaises(InvalidParameterValueException):
self.node.declare_parameters('', parameters)
with self.assertRaises(TypeError):
self.node.declare_parameters(
'',
[(
1,
'wrong_name_type',
ParameterDescriptor()
)]
)
with self.assertRaises(ValueError):
self.node.declare_parameters(
'',
[(
'wrong_parameter_value_type',
ParameterValue(),
ParameterDescriptor()
)]
)
with self.assertRaises(TypeError):
self.node.declare_parameters(
'',
[(
'wrong_parameter_descriptor_tpye',
ParameterValue(),
ParameterValue()
)]
)
# Declare a parameter with parameter type 'Not Set'
with self.assertRaises(ValueError):
self.node.declare_parameter(
'wrong_parameter_value_type_not_set', Parameter.Type.NOT_SET)
def reject_parameter_callback(self, parameter_list):
rejected_parameters = (param for param in parameter_list if 'reject' in param.name)
return SetParametersResult(successful=(not any(rejected_parameters)))