forked from rai-opensource/spatialmath-python
-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathsuper_pose.html
More file actions
1849 lines (1598 loc) · 165 KB
/
super_pose.html
File metadata and controls
1849 lines (1598 loc) · 165 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
<!DOCTYPE html>
<html xmlns="http://www.w3.org/1999/xhtml">
<head>
<meta charset="utf-8" />
<title>spatialmath.super_pose — Spatial Maths package 0.7.0
documentation</title>
<link rel="stylesheet" href="../../_static/alabaster.css" type="text/css" />
<link rel="stylesheet" href="../../_static/pygments.css" type="text/css" />
<link rel="stylesheet" type="text/css" href="../../_static/graphviz.css" />
<script id="documentation_options" data-url_root="../../" src="../../_static/documentation_options.js"></script>
<script src="../../_static/jquery.js"></script>
<script src="../../_static/underscore.js"></script>
<script src="../../_static/doctools.js"></script>
<script src="../../_static/language_data.js"></script>
<script async="async" src="https://cdnjs.cloudflare.com/ajax/libs/mathjax/2.7.5/latest.js?config=TeX-AMS-MML_HTMLorMML"></script>
<link rel="index" title="Index" href="../../genindex.html" />
<link rel="search" title="Search" href="../../search.html" />
<link rel="stylesheet" href="../../_static/custom.css" type="text/css" />
<meta name="viewport" content="width=device-width, initial-scale=0.9, maximum-scale=0.9" />
</head><body>
<div class="document">
<div class="documentwrapper">
<div class="bodywrapper">
<div class="body" role="main">
<h1>Source code for spatialmath.super_pose</h1><div class="highlight"><pre>
<span></span><span class="c1"># Created by: Aditya Dua, 2017</span>
<span class="c1"># Peter Corke, 2020</span>
<span class="c1"># 13 June, 2017</span>
<span class="kn">import</span> <span class="nn">numpy</span> <span class="k">as</span> <span class="nn">np</span>
<span class="kn">import</span> <span class="nn">sympy</span>
<span class="kn">from</span> <span class="nn">collections</span> <span class="kn">import</span> <span class="n">UserList</span>
<span class="kn">import</span> <span class="nn">copy</span>
<span class="kn">from</span> <span class="nn">spatialmath.base</span> <span class="kn">import</span> <span class="n">argcheck</span>
<span class="kn">import</span> <span class="nn">spatialmath.base</span> <span class="k">as</span> <span class="nn">tr</span>
<span class="n">_eps</span> <span class="o">=</span> <span class="n">np</span><span class="o">.</span><span class="n">finfo</span><span class="p">(</span><span class="n">np</span><span class="o">.</span><span class="n">float64</span><span class="p">)</span><span class="o">.</span><span class="n">eps</span>
<span class="c1"># colored printing of matrices to the terminal</span>
<span class="c1"># colored package has much finer control than colorama, but the latter is available by default with anaconda</span>
<span class="k">try</span><span class="p">:</span>
<span class="kn">from</span> <span class="nn">colored</span> <span class="kn">import</span> <span class="n">fg</span><span class="p">,</span> <span class="n">bg</span><span class="p">,</span> <span class="n">attr</span>
<span class="n">_color</span> <span class="o">=</span> <span class="kc">True</span>
<span class="nb">print</span><span class="p">(</span><span class="s1">'using colored output'</span><span class="p">)</span>
<span class="k">except</span><span class="p">:</span>
<span class="c1">#print('colored not found')</span>
<span class="n">_color</span> <span class="o">=</span> <span class="kc">False</span>
<span class="c1"># try:</span>
<span class="c1"># import colorama</span>
<span class="c1"># colorama.init()</span>
<span class="c1"># print('using colored output')</span>
<span class="c1"># from colorama import Fore, Back, Style</span>
<span class="c1"># except:</span>
<span class="c1"># class color:</span>
<span class="c1"># def __init__(self):</span>
<span class="c1"># self.RED = ''</span>
<span class="c1"># self.BLUE = ''</span>
<span class="c1"># self.BLACK = ''</span>
<span class="c1"># self.DIM = ''</span>
<span class="c1"># print(Fore.RED + '1.00 2.00 ' + Fore.BLUE + '3.00')</span>
<span class="c1"># print(Fore.RED + '1.00 2.00 ' + Fore.BLUE + '3.00')</span>
<span class="c1"># print(Fore.BLACK + Style.DIM + '0 0 1')</span>
<span class="k">class</span> <span class="nc">SMPose</span><span class="p">(</span><span class="n">UserList</span><span class="p">):</span>
<span class="sd">"""</span>
<span class="sd"> Superclass for SO(N) and SE(N) objects</span>
<span class="sd"> Subclasses are:</span>
<span class="sd"> - ``SO2`` representing elements of SO(2) which describe rotations in 2D</span>
<span class="sd"> - ``SE2`` representing elements of SE(2) which describe rigid-body motion in 2D</span>
<span class="sd"> - ``SO3`` representing elements of SO(3) which describe rotations in 3D</span>
<span class="sd"> - ``SE3`` representing elements of SE(3) which describe rigid-body motion in 3D</span>
<span class="sd"> Arithmetic operators are overloaded but the operation they perform depend</span>
<span class="sd"> on the types of the operands. For example:</span>
<span class="sd"> - ``*`` will compose two instances of the same subclass, and the result will be</span>
<span class="sd"> an instance of the same subclass, since this is a group operator.</span>
<span class="sd"> - ``+`` will add two instances of the same subclass, and the result will be</span>
<span class="sd"> a matrix, not an instance of the same subclass, since addition is not a group operator.</span>
<span class="sd"> These classes all inherit from ``UserList`` which enables them to </span>
<span class="sd"> represent a sequence of values, ie. an ``SE3`` instance can contain</span>
<span class="sd"> a sequence of SE(3) values. Most of the Python ``list`` operators</span>
<span class="sd"> are applicable::</span>
<span class="sd"> >>> x = SE3() # new instance with identity matrix value</span>
<span class="sd"> >>> len(x) # it is a sequence of one value</span>
<span class="sd"> 1</span>
<span class="sd"> >>> x.append(x) # append to itself</span>
<span class="sd"> >>> len(x) # it is a sequence of two values</span>
<span class="sd"> 2</span>
<span class="sd"> >>> x[1] # the element has a 4x4 matrix value</span>
<span class="sd"> SE3([</span>
<span class="sd"> array([[1., 0., 0., 0.],</span>
<span class="sd"> [0., 1., 0., 0.],</span>
<span class="sd"> [0., 0., 1., 0.],</span>
<span class="sd"> [0., 0., 0., 1.]]) ])</span>
<span class="sd"> >>> x[1] = SE3.Rx(0.3) # set an elements of the sequence</span>
<span class="sd"> >>> x.reverse() # reverse the elements in the sequence</span>
<span class="sd"> >>> del x[1] # delete an element</span>
<span class="sd"> """</span>
<span class="k">def</span> <span class="fm">__new__</span><span class="p">(</span><span class="bp">cls</span><span class="p">,</span> <span class="o">*</span><span class="n">args</span><span class="p">,</span> <span class="o">**</span><span class="n">kwargs</span><span class="p">):</span>
<span class="sd">"""</span>
<span class="sd"> Create the subclass instance (superclass method)</span>
<span class="sd"> Create a new instance and call the superclass initializer to enable the </span>
<span class="sd"> ``UserList`` capabilities.</span>
<span class="sd"> """</span>
<span class="n">pose</span> <span class="o">=</span> <span class="nb">super</span><span class="p">(</span><span class="n">SMPose</span><span class="p">,</span> <span class="bp">cls</span><span class="p">)</span><span class="o">.</span><span class="fm">__new__</span><span class="p">(</span><span class="bp">cls</span><span class="p">)</span> <span class="c1"># create a new instance</span>
<span class="nb">super</span><span class="p">()</span><span class="o">.</span><span class="fm">__init__</span><span class="p">(</span><span class="n">pose</span><span class="p">)</span> <span class="c1"># initialize UserList</span>
<span class="k">return</span> <span class="n">pose</span>
<span class="k">def</span> <span class="nf">_arghandler</span><span class="p">(</span><span class="bp">self</span><span class="p">,</span> <span class="n">arg</span><span class="p">,</span> <span class="n">check</span><span class="o">=</span><span class="kc">True</span><span class="p">):</span>
<span class="sd">"""</span>
<span class="sd"> Assign value to pose subclasses (superclass method)</span>
<span class="sd"> </span>
<span class="sd"> :param self: the pose object to be set</span>
<span class="sd"> :type self: SO2, SE2, SO3, SE3 instance</span>
<span class="sd"> :param arg: value of pose</span>
<span class="sd"> :param check: check type of argument, defaults to True</span>
<span class="sd"> :type check: TYPE, optional</span>
<span class="sd"> :raises ValueError: bad type passed</span>
<span class="sd"> The value ``arg`` can be any of:</span>
<span class="sd"> </span>
<span class="sd"> # a numpy.ndarray of the appropriate shape and value which is valid for the subclass</span>
<span class="sd"> # a list whose elements all meet the criteria above</span>
<span class="sd"> # an instance of the subclass</span>
<span class="sd"> # a list whose elements are all instances of the subclass</span>
<span class="sd"> </span>
<span class="sd"> Examples::</span>
<span class="sd"> SE3( np.identity(4))</span>
<span class="sd"> SE3( [np.identity(4), np.identity(4)])</span>
<span class="sd"> SE3( SE3() )</span>
<span class="sd"> SE3( [SE3(), SE3()])</span>
<span class="sd"> """</span>
<span class="k">if</span> <span class="nb">isinstance</span><span class="p">(</span><span class="n">arg</span><span class="p">,</span> <span class="n">np</span><span class="o">.</span><span class="n">ndarray</span><span class="p">):</span>
<span class="c1"># it's a numpy array</span>
<span class="k">assert</span> <span class="n">arg</span><span class="o">.</span><span class="n">shape</span> <span class="o">==</span> <span class="bp">self</span><span class="o">.</span><span class="n">shape</span><span class="p">,</span> <span class="s1">'array must have valid shape for the class'</span>
<span class="k">assert</span> <span class="nb">type</span><span class="p">(</span><span class="bp">self</span><span class="p">)</span><span class="o">.</span><span class="n">isvalid</span><span class="p">(</span><span class="n">arg</span><span class="p">),</span> <span class="s1">'array must have valid value for the class'</span>
<span class="bp">self</span><span class="o">.</span><span class="n">data</span><span class="o">.</span><span class="n">append</span><span class="p">(</span><span class="n">arg</span><span class="p">)</span>
<span class="k">elif</span> <span class="nb">isinstance</span><span class="p">(</span><span class="n">arg</span><span class="p">,</span> <span class="nb">list</span><span class="p">):</span>
<span class="c1"># construct from a list</span>
<span class="k">if</span> <span class="nb">isinstance</span><span class="p">(</span><span class="n">arg</span><span class="p">[</span><span class="mi">0</span><span class="p">],</span> <span class="n">np</span><span class="o">.</span><span class="n">ndarray</span><span class="p">):</span>
<span class="c1">#print('list of numpys')</span>
<span class="c1"># possibly a list of numpy arrays</span>
<span class="n">s</span> <span class="o">=</span> <span class="bp">self</span><span class="o">.</span><span class="n">shape</span>
<span class="k">if</span> <span class="n">check</span><span class="p">:</span>
<span class="n">checkfunc</span> <span class="o">=</span> <span class="nb">type</span><span class="p">(</span><span class="bp">self</span><span class="p">)</span><span class="o">.</span><span class="n">isvalid</span> <span class="c1"># lambda function</span>
<span class="k">assert</span> <span class="nb">all</span><span class="p">(</span><span class="nb">map</span><span class="p">(</span><span class="k">lambda</span> <span class="n">x</span><span class="p">:</span> <span class="n">x</span><span class="o">.</span><span class="n">shape</span> <span class="o">==</span> <span class="n">s</span> <span class="ow">and</span> <span class="n">checkfunc</span><span class="p">(</span><span class="n">x</span><span class="p">),</span> <span class="n">arg</span><span class="p">)),</span> <span class="s1">'all elements of list must have valid shape and value for the class'</span>
<span class="k">else</span><span class="p">:</span>
<span class="k">assert</span> <span class="nb">all</span><span class="p">(</span><span class="nb">map</span><span class="p">(</span><span class="k">lambda</span> <span class="n">x</span><span class="p">:</span> <span class="n">x</span><span class="o">.</span><span class="n">shape</span> <span class="o">==</span> <span class="n">s</span><span class="p">,</span> <span class="n">arg</span><span class="p">))</span>
<span class="bp">self</span><span class="o">.</span><span class="n">data</span> <span class="o">=</span> <span class="n">arg</span>
<span class="k">elif</span> <span class="nb">type</span><span class="p">(</span><span class="n">arg</span><span class="p">[</span><span class="mi">0</span><span class="p">])</span> <span class="o">==</span> <span class="nb">type</span><span class="p">(</span><span class="bp">self</span><span class="p">):</span>
<span class="c1"># possibly a list of objects of same type</span>
<span class="k">assert</span> <span class="nb">all</span><span class="p">(</span><span class="nb">map</span><span class="p">(</span><span class="k">lambda</span> <span class="n">x</span><span class="p">:</span> <span class="nb">type</span><span class="p">(</span><span class="n">x</span><span class="p">)</span> <span class="o">==</span> <span class="nb">type</span><span class="p">(</span><span class="bp">self</span><span class="p">),</span> <span class="n">arg</span><span class="p">)),</span> <span class="s1">'all elements of list must have same type'</span>
<span class="bp">self</span><span class="o">.</span><span class="n">data</span> <span class="o">=</span> <span class="p">[</span><span class="n">x</span><span class="o">.</span><span class="n">A</span> <span class="k">for</span> <span class="n">x</span> <span class="ow">in</span> <span class="n">arg</span><span class="p">]</span>
<span class="k">else</span><span class="p">:</span>
<span class="k">raise</span> <span class="ne">ValueError</span><span class="p">(</span><span class="s1">'bad list argument to constructor'</span><span class="p">)</span>
<span class="k">elif</span> <span class="nb">type</span><span class="p">(</span><span class="bp">self</span><span class="p">)</span> <span class="o">==</span> <span class="nb">type</span><span class="p">(</span><span class="n">arg</span><span class="p">):</span>
<span class="c1"># it's an object of same type, do copy</span>
<span class="bp">self</span><span class="o">.</span><span class="n">data</span> <span class="o">=</span> <span class="n">arg</span><span class="o">.</span><span class="n">data</span><span class="o">.</span><span class="n">copy</span><span class="p">()</span>
<span class="k">else</span><span class="p">:</span>
<span class="k">raise</span> <span class="ne">ValueError</span><span class="p">(</span><span class="s1">'bad argument to constructor'</span><span class="p">)</span>
<span class="nd">@classmethod</span>
<span class="k">def</span> <span class="nf">Empty</span><span class="p">(</span><span class="bp">cls</span><span class="p">):</span>
<span class="sd">"""</span>
<span class="sd"> Construct a new pose object with zero items (superclass method)</span>
<span class="sd"> </span>
<span class="sd"> :param cls: The pose subclass</span>
<span class="sd"> :type cls: SO2, SE2, SO3, SE3</span>
<span class="sd"> :return: a pose with zero values</span>
<span class="sd"> :rtype: SO2, SE2, SO3, SE3 instance</span>
<span class="sd"> This constructs an empty pose container which can be appended to. For example::</span>
<span class="sd"> </span>
<span class="sd"> >>> x = SO2.Empty()</span>
<span class="sd"> >>> len(x)</span>
<span class="sd"> 0</span>
<span class="sd"> >>> x.append(SO2(20, 'deg'))</span>
<span class="sd"> >>> len(x)</span>
<span class="sd"> 1</span>
<span class="sd"> </span>
<span class="sd"> """</span>
<span class="n">X</span> <span class="o">=</span> <span class="bp">cls</span><span class="p">()</span>
<span class="n">X</span><span class="o">.</span><span class="n">data</span> <span class="o">=</span> <span class="p">[]</span>
<span class="k">return</span> <span class="n">X</span>
<span class="c1"># ------------------------------------------------------------------------ #</span>
<span class="nd">@property</span>
<span class="k">def</span> <span class="nf">A</span><span class="p">(</span><span class="bp">self</span><span class="p">):</span>
<span class="sd">"""</span>
<span class="sd"> Interal array representation (superclass property)</span>
<span class="sd"> </span>
<span class="sd"> :param self: the pose object</span>
<span class="sd"> :type self: SO2, SE2, SO3, SE3 instance</span>
<span class="sd"> :return: The numeric array</span>
<span class="sd"> :rtype: numpy.ndarray</span>
<span class="sd"> </span>
<span class="sd"> Each pose subclass SO(N) or SE(N) are stored internally as a numpy array. This property returns</span>
<span class="sd"> the array, shape depends on the particular subclass.</span>
<span class="sd"> </span>
<span class="sd"> Examples::</span>
<span class="sd"> </span>
<span class="sd"> >>> x = SE3()</span>
<span class="sd"> >>> x.A</span>
<span class="sd"> array([[1., 0., 0., 0.],</span>
<span class="sd"> [0., 1., 0., 0.],</span>
<span class="sd"> [0., 0., 1., 0.],</span>
<span class="sd"> [0., 0., 0., 1.]])</span>
<span class="sd"> :seealso: `shape`, `N`</span>
<span class="sd"> """</span>
<span class="c1"># get the underlying numpy array</span>
<span class="k">if</span> <span class="nb">len</span><span class="p">(</span><span class="bp">self</span><span class="o">.</span><span class="n">data</span><span class="p">)</span> <span class="o">==</span> <span class="mi">1</span><span class="p">:</span>
<span class="k">return</span> <span class="bp">self</span><span class="o">.</span><span class="n">data</span><span class="p">[</span><span class="mi">0</span><span class="p">]</span>
<span class="k">else</span><span class="p">:</span>
<span class="k">return</span> <span class="bp">self</span><span class="o">.</span><span class="n">data</span>
<span class="nd">@property</span>
<span class="k">def</span> <span class="nf">shape</span><span class="p">(</span><span class="bp">self</span><span class="p">):</span>
<span class="sd">"""</span>
<span class="sd"> Shape of the object's matrix representation (superclass property)</span>
<span class="sd"> :return: matrix shape</span>
<span class="sd"> :rtype: 2-tuple of ints</span>
<span class="sd"> (2,2) for ``SO2``, (3,3) for ``SE2`` and ``SO3``, and (4,4) for ``SE3``.</span>
<span class="sd"> </span>
<span class="sd"> Example::</span>
<span class="sd"> </span>
<span class="sd"> >>> x = SE3()</span>
<span class="sd"> >>> x.shape</span>
<span class="sd"> (4, 4)</span>
<span class="sd"> """</span>
<span class="k">if</span> <span class="nb">type</span><span class="p">(</span><span class="bp">self</span><span class="p">)</span><span class="o">.</span><span class="vm">__name__</span> <span class="o">==</span> <span class="s1">'SO2'</span><span class="p">:</span>
<span class="k">return</span> <span class="p">(</span><span class="mi">2</span><span class="p">,</span> <span class="mi">2</span><span class="p">)</span>
<span class="k">elif</span> <span class="nb">type</span><span class="p">(</span><span class="bp">self</span><span class="p">)</span><span class="o">.</span><span class="vm">__name__</span> <span class="o">==</span> <span class="s1">'SO3'</span><span class="p">:</span>
<span class="k">return</span> <span class="p">(</span><span class="mi">3</span><span class="p">,</span> <span class="mi">3</span><span class="p">)</span>
<span class="k">elif</span> <span class="nb">type</span><span class="p">(</span><span class="bp">self</span><span class="p">)</span><span class="o">.</span><span class="vm">__name__</span> <span class="o">==</span> <span class="s1">'SE2'</span><span class="p">:</span>
<span class="k">return</span> <span class="p">(</span><span class="mi">3</span><span class="p">,</span> <span class="mi">3</span><span class="p">)</span>
<span class="k">elif</span> <span class="nb">type</span><span class="p">(</span><span class="bp">self</span><span class="p">)</span><span class="o">.</span><span class="vm">__name__</span> <span class="o">==</span> <span class="s1">'SE3'</span><span class="p">:</span>
<span class="k">return</span> <span class="p">(</span><span class="mi">4</span><span class="p">,</span> <span class="mi">4</span><span class="p">)</span>
<span class="nd">@property</span>
<span class="k">def</span> <span class="nf">about</span><span class="p">(</span><span class="bp">self</span><span class="p">):</span>
<span class="sd">"""</span>
<span class="sd"> Succinct summary of object type and length (superclass property)</span>
<span class="sd"> :return: succinct summary</span>
<span class="sd"> :rtype: str</span>
<span class="sd"> Displays the type and the number of elements in compact form, for </span>
<span class="sd"> example::</span>
<span class="sd"> >>> x = SE3([SE3() for i in range(20)])</span>
<span class="sd"> >>> len(x)</span>
<span class="sd"> 20</span>
<span class="sd"> >>> print(x.about)</span>
<span class="sd"> SE3[20]</span>
<span class="sd"> """</span>
<span class="k">return</span> <span class="s2">"</span><span class="si">{:s}</span><span class="s2">[</span><span class="si">{:d}</span><span class="s2">]"</span><span class="o">.</span><span class="n">format</span><span class="p">(</span><span class="nb">type</span><span class="p">(</span><span class="bp">self</span><span class="p">)</span><span class="o">.</span><span class="vm">__name__</span><span class="p">,</span> <span class="nb">len</span><span class="p">(</span><span class="bp">self</span><span class="p">))</span>
<span class="nd">@property</span>
<span class="k">def</span> <span class="nf">N</span><span class="p">(</span><span class="bp">self</span><span class="p">):</span>
<span class="sd">"""</span>
<span class="sd"> Dimension of the object's group (superclass property)</span>
<span class="sd"> :return: dimension</span>
<span class="sd"> :rtype: int</span>
<span class="sd"> Dimension of the group is 2 for ``SO2`` or ``SE2``, and 3 for ``SO3`` or ``SE3``.</span>
<span class="sd"> This corresponds to the dimension of the space, 2D or 3D, to which these</span>
<span class="sd"> rotations or rigid-body motions apply.</span>
<span class="sd"> </span>
<span class="sd"> Example::</span>
<span class="sd"> </span>
<span class="sd"> >>> x = SE3()</span>
<span class="sd"> >>> x.N</span>
<span class="sd"> 3</span>
<span class="sd"> """</span>
<span class="k">if</span> <span class="nb">type</span><span class="p">(</span><span class="bp">self</span><span class="p">)</span><span class="o">.</span><span class="vm">__name__</span> <span class="o">==</span> <span class="s1">'SO2'</span> <span class="ow">or</span> <span class="nb">type</span><span class="p">(</span><span class="bp">self</span><span class="p">)</span><span class="o">.</span><span class="vm">__name__</span> <span class="o">==</span> <span class="s1">'SE2'</span><span class="p">:</span>
<span class="k">return</span> <span class="mi">2</span>
<span class="k">else</span><span class="p">:</span>
<span class="k">return</span> <span class="mi">3</span>
<span class="c1">#----------------------- tests</span>
<span class="nd">@property</span>
<span class="k">def</span> <span class="nf">isSO</span><span class="p">(</span><span class="bp">self</span><span class="p">):</span>
<span class="sd">"""</span>
<span class="sd"> Test if object belongs to SO(n) group (superclass property)</span>
<span class="sd"> :param self: object to test</span>
<span class="sd"> :type self: SO2, SE2, SO3, SE3 instance</span>
<span class="sd"> :return: ``True`` if object is instance of SO2 or SO3</span>
<span class="sd"> :rtype: bool</span>
<span class="sd"> """</span>
<span class="k">return</span> <span class="nb">type</span><span class="p">(</span><span class="bp">self</span><span class="p">)</span><span class="o">.</span><span class="vm">__name__</span> <span class="o">==</span> <span class="s1">'SO2'</span> <span class="ow">or</span> <span class="nb">type</span><span class="p">(</span><span class="bp">self</span><span class="p">)</span><span class="o">.</span><span class="vm">__name__</span> <span class="o">==</span> <span class="s1">'SO3'</span>
<span class="nd">@property</span>
<span class="k">def</span> <span class="nf">isSE</span><span class="p">(</span><span class="bp">self</span><span class="p">):</span>
<span class="sd">"""</span>
<span class="sd"> Test if object belongs to SE(n) group (superclass property)</span>
<span class="sd"> :param self: object to test</span>
<span class="sd"> :type self: SO2, SE2, SO3, SE3 instance</span>
<span class="sd"> :return: ``True`` if object is instance of SE2 or SE3</span>
<span class="sd"> :rtype: bool</span>
<span class="sd"> """</span>
<span class="k">return</span> <span class="nb">type</span><span class="p">(</span><span class="bp">self</span><span class="p">)</span><span class="o">.</span><span class="vm">__name__</span> <span class="o">==</span> <span class="s1">'SE2'</span> <span class="ow">or</span> <span class="nb">type</span><span class="p">(</span><span class="bp">self</span><span class="p">)</span><span class="o">.</span><span class="vm">__name__</span> <span class="o">==</span> <span class="s1">'SE3'</span>
<span class="c1"># ------------------------------------------------------------------------ #</span>
<span class="k">def</span> <span class="fm">__getitem__</span><span class="p">(</span><span class="bp">self</span><span class="p">,</span> <span class="n">i</span><span class="p">):</span>
<span class="sd">"""</span>
<span class="sd"> Access value of a pose object (superclass method)</span>
<span class="sd"> :param i: index of element to return</span>
<span class="sd"> :type i: int</span>
<span class="sd"> :return: the specific element of the pose</span>
<span class="sd"> :rtype: SO2, SE2, SO3, SE3 instance</span>
<span class="sd"> :raises IndexError: if the element is out of bounds</span>
<span class="sd"> Note that only a single index is supported, slices are not.</span>
<span class="sd"> </span>
<span class="sd"> Example::</span>
<span class="sd"> </span>
<span class="sd"> >>> x = SE3.Rx([0, math.pi/2, math.pi])</span>
<span class="sd"> >>> len(x)</span>
<span class="sd"> 3</span>
<span class="sd"> >>> x[1]</span>
<span class="sd"> 1 0 0 0 </span>
<span class="sd"> 0 0 -1 0 </span>
<span class="sd"> 0 1 0 0 </span>
<span class="sd"> 0 0 0 1 </span>
<span class="sd"> """</span>
<span class="k">if</span> <span class="nb">isinstance</span><span class="p">(</span><span class="n">i</span><span class="p">,</span> <span class="nb">slice</span><span class="p">):</span>
<span class="k">return</span> <span class="bp">self</span><span class="o">.</span><span class="vm">__class__</span><span class="p">([</span><span class="bp">self</span><span class="o">.</span><span class="n">data</span><span class="p">[</span><span class="n">k</span><span class="p">]</span> <span class="k">for</span> <span class="n">k</span> <span class="ow">in</span> <span class="nb">range</span><span class="p">(</span><span class="n">i</span><span class="o">.</span><span class="n">start</span> <span class="ow">or</span> <span class="mi">0</span><span class="p">,</span> <span class="n">i</span><span class="o">.</span><span class="n">stop</span> <span class="ow">or</span> <span class="nb">len</span><span class="p">(</span><span class="bp">self</span><span class="p">),</span> <span class="n">i</span><span class="o">.</span><span class="n">step</span> <span class="ow">or</span> <span class="mi">1</span><span class="p">)])</span>
<span class="k">else</span><span class="p">:</span>
<span class="k">return</span> <span class="bp">self</span><span class="o">.</span><span class="vm">__class__</span><span class="p">(</span><span class="bp">self</span><span class="o">.</span><span class="n">data</span><span class="p">[</span><span class="n">i</span><span class="p">])</span>
<span class="k">def</span> <span class="fm">__setitem__</span><span class="p">(</span><span class="bp">self</span><span class="p">,</span> <span class="n">i</span><span class="p">,</span> <span class="n">value</span><span class="p">):</span>
<span class="sd">"""</span>
<span class="sd"> Assign a value to a pose object (superclass method)</span>
<span class="sd"> </span>
<span class="sd"> :param i: index of element to assign to</span>
<span class="sd"> :type i: int</span>
<span class="sd"> :param value: the value to insert</span>
<span class="sd"> :type value: SO2, SE2, SO3, SE3 instance</span>
<span class="sd"> :raises ValueError: incorrect type of assigned value</span>
<span class="sd"> Assign the argument to an element of the object's internal list of values.</span>
<span class="sd"> This supports the assignement operator, for example::</span>
<span class="sd"> </span>
<span class="sd"> >>> x = SE3([SE3() for i in range(10)]) # sequence of ten identity values</span>
<span class="sd"> >>> len(x)</span>
<span class="sd"> 10</span>
<span class="sd"> >>> x[3] = SE3.Rx(0.2) # assign to position 3 in the list</span>
<span class="sd"> """</span>
<span class="k">if</span> <span class="ow">not</span> <span class="nb">type</span><span class="p">(</span><span class="bp">self</span><span class="p">)</span> <span class="o">==</span> <span class="nb">type</span><span class="p">(</span><span class="n">value</span><span class="p">):</span>
<span class="k">raise</span> <span class="ne">ValueError</span><span class="p">(</span><span class="s2">"cant append different type of pose object"</span><span class="p">)</span>
<span class="k">if</span> <span class="nb">len</span><span class="p">(</span><span class="n">value</span><span class="p">)</span> <span class="o">></span> <span class="mi">1</span><span class="p">:</span>
<span class="k">raise</span> <span class="ne">ValueError</span><span class="p">(</span><span class="s2">"cant insert a pose sequence - must have len() == 1"</span><span class="p">)</span>
<span class="bp">self</span><span class="o">.</span><span class="n">data</span><span class="p">[</span><span class="n">i</span><span class="p">]</span> <span class="o">=</span> <span class="n">value</span><span class="o">.</span><span class="n">A</span>
<span class="k">def</span> <span class="nf">append</span><span class="p">(</span><span class="bp">self</span><span class="p">,</span> <span class="n">x</span><span class="p">):</span>
<span class="sd">"""</span>
<span class="sd"> Append a value to a pose object (superclass method)</span>
<span class="sd"> </span>
<span class="sd"> :param x: the value to append</span>
<span class="sd"> :type x: SO2, SE2, SO3, SE3 instance</span>
<span class="sd"> :raises ValueError: incorrect type of appended object</span>
<span class="sd"> Appends the argument to the object's internal list of values.</span>
<span class="sd"> </span>
<span class="sd"> Examples::</span>
<span class="sd"> </span>
<span class="sd"> >>> x = SE3()</span>
<span class="sd"> >>> len(x)</span>
<span class="sd"> 1</span>
<span class="sd"> >>> x.append(SE3.Rx(0.1))</span>
<span class="sd"> >>> len(x)</span>
<span class="sd"> 2</span>
<span class="sd"> """</span>
<span class="c1">#print('in append method')</span>
<span class="k">if</span> <span class="ow">not</span> <span class="nb">type</span><span class="p">(</span><span class="bp">self</span><span class="p">)</span> <span class="o">==</span> <span class="nb">type</span><span class="p">(</span><span class="n">x</span><span class="p">):</span>
<span class="k">raise</span> <span class="ne">ValueError</span><span class="p">(</span><span class="s2">"cant append different type of pose object"</span><span class="p">)</span>
<span class="k">if</span> <span class="nb">len</span><span class="p">(</span><span class="n">x</span><span class="p">)</span> <span class="o">></span> <span class="mi">1</span><span class="p">:</span>
<span class="k">raise</span> <span class="ne">ValueError</span><span class="p">(</span><span class="s2">"cant append a pose sequence - use extend"</span><span class="p">)</span>
<span class="nb">super</span><span class="p">()</span><span class="o">.</span><span class="n">append</span><span class="p">(</span><span class="n">x</span><span class="o">.</span><span class="n">A</span><span class="p">)</span>
<span class="k">def</span> <span class="nf">extend</span><span class="p">(</span><span class="bp">self</span><span class="p">,</span> <span class="n">x</span><span class="p">):</span>
<span class="sd">"""</span>
<span class="sd"> Extend sequence of values of a pose object (superclass method)</span>
<span class="sd"> </span>
<span class="sd"> :param x: the value to extend</span>
<span class="sd"> :type x: SO2, SE2, SO3, SE3 instance</span>
<span class="sd"> :raises ValueError: incorrect type of appended object</span>
<span class="sd"> Appends the argument to the object's internal list of values.</span>
<span class="sd"> </span>
<span class="sd"> Examples::</span>
<span class="sd"> </span>
<span class="sd"> >>> x = SE3()</span>
<span class="sd"> >>> len(x)</span>
<span class="sd"> 1</span>
<span class="sd"> >>> x.append(SE3.Rx(0.1))</span>
<span class="sd"> >>> len(x)</span>
<span class="sd"> 2</span>
<span class="sd"> """</span>
<span class="c1">#print('in extend method')</span>
<span class="k">if</span> <span class="ow">not</span> <span class="nb">type</span><span class="p">(</span><span class="bp">self</span><span class="p">)</span> <span class="o">==</span> <span class="nb">type</span><span class="p">(</span><span class="n">x</span><span class="p">):</span>
<span class="k">raise</span> <span class="ne">ValueError</span><span class="p">(</span><span class="s2">"cant append different type of pose object"</span><span class="p">)</span>
<span class="k">if</span> <span class="nb">len</span><span class="p">(</span><span class="n">x</span><span class="p">)</span> <span class="o">==</span> <span class="mi">0</span><span class="p">:</span>
<span class="k">raise</span> <span class="ne">ValueError</span><span class="p">(</span><span class="s2">"cant extend a singleton pose - use append"</span><span class="p">)</span>
<span class="nb">super</span><span class="p">()</span><span class="o">.</span><span class="n">extend</span><span class="p">(</span><span class="n">x</span><span class="o">.</span><span class="n">A</span><span class="p">)</span>
<span class="k">def</span> <span class="nf">insert</span><span class="p">(</span><span class="bp">self</span><span class="p">,</span> <span class="n">i</span><span class="p">,</span> <span class="n">value</span><span class="p">):</span>
<span class="sd">"""</span>
<span class="sd"> Insert a value to a pose object (superclass method)</span>
<span class="sd"> :param i: element to insert value before</span>
<span class="sd"> :type i: int</span>
<span class="sd"> :param value: the value to insert</span>
<span class="sd"> :type value: SO2, SE2, SO3, SE3 instance</span>
<span class="sd"> :raises ValueError: incorrect type of inserted value</span>
<span class="sd"> Inserts the argument into the object's internal list of values.</span>
<span class="sd"> </span>
<span class="sd"> Examples::</span>
<span class="sd"> </span>
<span class="sd"> >>> x = SE3()</span>
<span class="sd"> >>> x.inert(0, SE3.Rx(0.1)) # insert at position 0 in the list</span>
<span class="sd"> >>> len(x)</span>
<span class="sd"> 2</span>
<span class="sd"> """</span>
<span class="k">if</span> <span class="ow">not</span> <span class="nb">type</span><span class="p">(</span><span class="bp">self</span><span class="p">)</span> <span class="o">==</span> <span class="nb">type</span><span class="p">(</span><span class="n">value</span><span class="p">):</span>
<span class="k">raise</span> <span class="ne">ValueError</span><span class="p">(</span><span class="s2">"cant append different type of pose object"</span><span class="p">)</span>
<span class="k">if</span> <span class="nb">len</span><span class="p">(</span><span class="n">value</span><span class="p">)</span> <span class="o">></span> <span class="mi">1</span><span class="p">:</span>
<span class="k">raise</span> <span class="ne">ValueError</span><span class="p">(</span><span class="s2">"cant insert a pose sequence - must have len() == 1"</span><span class="p">)</span>
<span class="nb">super</span><span class="p">()</span><span class="o">.</span><span class="n">insert</span><span class="p">(</span><span class="n">i</span><span class="p">,</span> <span class="n">value</span><span class="o">.</span><span class="n">A</span><span class="p">)</span>
<span class="k">def</span> <span class="nf">pop</span><span class="p">(</span><span class="bp">self</span><span class="p">):</span>
<span class="sd">"""</span>
<span class="sd"> Pop value of a pose object (superclass method)</span>
<span class="sd"> :return: the specific element of the pose</span>
<span class="sd"> :rtype: SO2, SE2, SO3, SE3 instance</span>
<span class="sd"> :raises IndexError: if there are no values to pop</span>
<span class="sd"> Removes the first pose value from the sequence in the pose object.</span>
<span class="sd"> </span>
<span class="sd"> Example::</span>
<span class="sd"> </span>
<span class="sd"> >>> x = SE3.Rx([0, math.pi/2, math.pi])</span>
<span class="sd"> >>> len(x)</span>
<span class="sd"> 3</span>
<span class="sd"> >>> y = x.pop()</span>
<span class="sd"> >>> y</span>
<span class="sd"> SE3(array([[ 1.0000000e+00, 0.0000000e+00, 0.0000000e+00, 0.0000000e+00],</span>
<span class="sd"> [ 0.0000000e+00, -1.0000000e+00, -1.2246468e-16, 0.0000000e+00],</span>
<span class="sd"> [ 0.0000000e+00, 1.2246468e-16, -1.0000000e+00, 0.0000000e+00],</span>
<span class="sd"> [ 0.0000000e+00, 0.0000000e+00, 0.0000000e+00, 1.0000000e+00]]))</span>
<span class="sd"> >>> len(x)</span>
<span class="sd"> 2</span>
<span class="sd"> """</span>
<span class="k">return</span> <span class="bp">self</span><span class="o">.</span><span class="vm">__class__</span><span class="p">(</span><span class="nb">super</span><span class="p">()</span><span class="o">.</span><span class="n">pop</span><span class="p">())</span>
<span class="c1"># ------------------------------------------------------------------------ #</span>
<span class="c1"># --------- compatibility methods</span>
<span class="k">def</span> <span class="nf">isrot</span><span class="p">(</span><span class="bp">self</span><span class="p">):</span>
<span class="sd">"""</span>
<span class="sd"> Test if object belongs to SO(3) group (superclass method)</span>
<span class="sd"> :return: ``True`` if object is instance of SO3</span>
<span class="sd"> :rtype: bool</span>
<span class="sd"> For compatibility with Spatial Math Toolbox for MATLAB.</span>
<span class="sd"> In Python use ``isinstance(x, SO3)``.</span>
<span class="sd"> </span>
<span class="sd"> Example::</span>
<span class="sd"> </span>
<span class="sd"> >>> x = SO3()</span>
<span class="sd"> >>> x.isrot()</span>
<span class="sd"> True</span>
<span class="sd"> >>> x = SE3()</span>
<span class="sd"> >>> x.isrot()</span>
<span class="sd"> False</span>
<span class="sd"> """</span>
<span class="k">return</span> <span class="nb">type</span><span class="p">(</span><span class="bp">self</span><span class="p">)</span><span class="o">.</span><span class="vm">__name__</span> <span class="o">==</span> <span class="s1">'SO3'</span>
<span class="k">def</span> <span class="nf">isrot2</span><span class="p">(</span><span class="bp">self</span><span class="p">):</span>
<span class="sd">"""</span>
<span class="sd"> Test if object belongs to SO(2) group (superclass method)</span>
<span class="sd"> :return: ``True`` if object is instance of SO2</span>
<span class="sd"> :rtype: bool</span>
<span class="sd"> For compatibility with Spatial Math Toolbox for MATLAB.</span>
<span class="sd"> In Python use ``isinstance(x, SO2)``.</span>
<span class="sd"> Example::</span>
<span class="sd"> </span>
<span class="sd"> >>> x = SO2()</span>
<span class="sd"> >>> x.isrot()</span>
<span class="sd"> True</span>
<span class="sd"> >>> x = SE2()</span>
<span class="sd"> >>> x.isrot()</span>
<span class="sd"> False</span>
<span class="sd"> """</span>
<span class="k">return</span> <span class="nb">type</span><span class="p">(</span><span class="bp">self</span><span class="p">)</span><span class="o">.</span><span class="vm">__name__</span> <span class="o">==</span> <span class="s1">'SO2'</span>
<span class="k">def</span> <span class="nf">ishom</span><span class="p">(</span><span class="bp">self</span><span class="p">):</span>
<span class="sd">"""</span>
<span class="sd"> Test if object belongs to SE(3) group (superclass method)</span>
<span class="sd"> :return: ``True`` if object is instance of SE3</span>
<span class="sd"> :rtype: bool</span>
<span class="sd"> For compatibility with Spatial Math Toolbox for MATLAB.</span>
<span class="sd"> In Python use ``isinstance(x, SE3)``.</span>
<span class="sd"> </span>
<span class="sd"> Example::</span>
<span class="sd"> </span>
<span class="sd"> >>> x = SO3()</span>
<span class="sd"> >>> x.isrot()</span>
<span class="sd"> False</span>
<span class="sd"> >>> x = SE3()</span>
<span class="sd"> >>> x.isrot()</span>
<span class="sd"> True</span>
<span class="sd"> """</span>
<span class="k">return</span> <span class="nb">type</span><span class="p">(</span><span class="bp">self</span><span class="p">)</span><span class="o">.</span><span class="vm">__name__</span> <span class="o">==</span> <span class="s1">'SE3'</span>
<span class="k">def</span> <span class="nf">ishom2</span><span class="p">(</span><span class="bp">self</span><span class="p">):</span>
<span class="sd">"""</span>
<span class="sd"> Test if object belongs to SE(2) group (superclass method)</span>
<span class="sd"> :return: ``True`` if object is instance of SE2</span>
<span class="sd"> :rtype: bool</span>
<span class="sd"> For compatibility with Spatial Math Toolbox for MATLAB.</span>
<span class="sd"> In Python use ``isinstance(x, SE2)``.</span>
<span class="sd"> </span>
<span class="sd"> Example::</span>
<span class="sd"> </span>
<span class="sd"> >>> x = SO2()</span>
<span class="sd"> >>> x.isrot()</span>
<span class="sd"> False</span>
<span class="sd"> >>> x = SE2()</span>
<span class="sd"> >>> x.isrot()</span>
<span class="sd"> True</span>
<span class="sd"> """</span>
<span class="k">return</span> <span class="nb">type</span><span class="p">(</span><span class="bp">self</span><span class="p">)</span><span class="o">.</span><span class="vm">__name__</span> <span class="o">==</span> <span class="s1">'SE2'</span>
<span class="c1">#----------------------- functions</span>
<span class="k">def</span> <span class="nf">log</span><span class="p">(</span><span class="bp">self</span><span class="p">):</span>
<span class="sd">"""</span>
<span class="sd"> Logarithm of pose (superclass method)</span>
<span class="sd"> :return: logarithm</span>
<span class="sd"> :rtype: numpy.ndarray</span>
<span class="sd"> :raises: ValueError</span>
<span class="sd"> </span>
<span class="sd"> An efficient closed-form solution of the matrix logarithm.</span>
<span class="sd"> </span>
<span class="sd"> ===== ====== ===============================</span>
<span class="sd"> Input Output</span>
<span class="sd"> ----- ---------------------------------------</span>
<span class="sd"> Pose Shape Structure</span>
<span class="sd"> ===== ====== ===============================</span>
<span class="sd"> SO2 (2,2) skew-symmetric</span>
<span class="sd"> SE2 (3,3) augmented skew-symmetric</span>
<span class="sd"> SO3 (3,3) skew-symmetric</span>
<span class="sd"> SE3 (4,4) augmented skew-symmetric</span>
<span class="sd"> ===== ====== ===============================</span>
<span class="sd"> </span>
<span class="sd"> Example::</span>
<span class="sd"> >>> x = SE3.Rx(0.3)</span>
<span class="sd"> >>> y = x.log()</span>
<span class="sd"> >>> y</span>
<span class="sd"> array([[ 0. , -0. , 0. , 0. ],</span>
<span class="sd"> [ 0. , 0. , -0.3, 0. ],</span>
<span class="sd"> [-0. , 0.3, 0. , 0. ],</span>
<span class="sd"> [ 0. , 0. , 0. , 0. ]])</span>
<span class="sd"> </span>
<span class="sd"> :seealso: :func:`~spatialmath.base.transforms2d.trlog2`, :func:`~spatialmath.base.transforms3d.trlog`</span>
<span class="sd"> """</span>
<span class="nb">print</span><span class="p">(</span><span class="s1">'in log'</span><span class="p">)</span>
<span class="k">if</span> <span class="bp">self</span><span class="o">.</span><span class="n">N</span> <span class="o">==</span> <span class="mi">2</span><span class="p">:</span>
<span class="n">log</span> <span class="o">=</span> <span class="p">[</span><span class="n">tr</span><span class="o">.</span><span class="n">trlog2</span><span class="p">(</span><span class="n">x</span><span class="p">)</span> <span class="k">for</span> <span class="n">x</span> <span class="ow">in</span> <span class="bp">self</span><span class="o">.</span><span class="n">data</span><span class="p">]</span>
<span class="k">else</span><span class="p">:</span>
<span class="n">log</span> <span class="o">=</span> <span class="p">[</span><span class="n">tr</span><span class="o">.</span><span class="n">trlog</span><span class="p">(</span><span class="n">x</span><span class="p">)</span> <span class="k">for</span> <span class="n">x</span> <span class="ow">in</span> <span class="bp">self</span><span class="o">.</span><span class="n">data</span><span class="p">]</span>
<span class="k">if</span> <span class="nb">len</span><span class="p">(</span><span class="n">log</span><span class="p">)</span> <span class="o">==</span> <span class="mi">1</span><span class="p">:</span>
<span class="k">return</span> <span class="n">log</span><span class="p">[</span><span class="mi">0</span><span class="p">]</span>
<span class="k">else</span><span class="p">:</span>
<span class="k">return</span> <span class="n">log</span>
<span class="k">def</span> <span class="nf">interp</span><span class="p">(</span><span class="bp">self</span><span class="p">,</span> <span class="n">s</span><span class="o">=</span><span class="kc">None</span><span class="p">,</span> <span class="n">T0</span><span class="o">=</span><span class="kc">None</span><span class="p">):</span>
<span class="sd">"""</span>
<span class="sd"> Interpolate pose (superclass method)</span>
<span class="sd"> </span>
<span class="sd"> :param T0: initial pose</span>
<span class="sd"> :type T0: SO2, SE2, SO3, SE3</span>
<span class="sd"> :param s: interpolation coefficient, range 0 to 1</span>
<span class="sd"> :type s: float or array_like</span>
<span class="sd"> :return: interpolated pose</span>
<span class="sd"> :rtype: SO2, SE2, SO3, SE3 instance</span>
<span class="sd"> </span>
<span class="sd"> - ``X.interp(s)`` interpolates the pose X between identity when s=0</span>
<span class="sd"> and X when s=1.</span>
<span class="sd"> ====== ====== =========== ===============================</span>
<span class="sd"> len(X) len(s) len(result) Result</span>
<span class="sd"> ====== ====== =========== ===============================</span>
<span class="sd"> 1 1 1 Y = interp(identity, X, s)</span>
<span class="sd"> M 1 M Y[i] = interp(T0, X[i], s)</span>
<span class="sd"> 1 M M Y[i] = interp(T0, X, s[i])</span>
<span class="sd"> ====== ====== =========== ===============================</span>
<span class="sd"> Example::</span>
<span class="sd"> </span>
<span class="sd"> >>> x = SE3.Rx(0.3)</span>
<span class="sd"> >>> print(x.interp(0))</span>
<span class="sd"> SE3(array([[1., 0., 0., 0.],</span>
<span class="sd"> [0., 1., 0., 0.],</span>
<span class="sd"> [0., 0., 1., 0.],</span>
<span class="sd"> [0., 0., 0., 1.]]))</span>
<span class="sd"> >>> print(x.interp(1))</span>
<span class="sd"> SE3(array([[ 1. , 0. , 0. , 0. ],</span>
<span class="sd"> [ 0. , 0.95533649, -0.29552021, 0. ],</span>
<span class="sd"> [ 0. , 0.29552021, 0.95533649, 0. ],</span>
<span class="sd"> [ 0. , 0. , 0. , 1. ]]))</span>
<span class="sd"> >>> y = x.interp(x, np.linspace(0, 1, 10))</span>
<span class="sd"> >>> len(y)</span>
<span class="sd"> 10</span>
<span class="sd"> >>> y[5]</span>
<span class="sd"> SE3(array([[ 1. , 0. , 0. , 0. ],</span>
<span class="sd"> [ 0. , 0.98614323, -0.16589613, 0. ],</span>
<span class="sd"> [ 0. , 0.16589613, 0.98614323, 0. ],</span>
<span class="sd"> [ 0. , 0. , 0. , 1. ]]))</span>
<span class="sd"> </span>
<span class="sd"> Notes:</span>
<span class="sd"> </span>
<span class="sd"> #. For SO3 and SE3 rotation is interpolated using quaternion spherical linear interpolation (slerp).</span>
<span class="sd"> </span>
<span class="sd"> :seealso: :func:`~spatialmath.base.transforms3d.trinterp`, :func:`spatialmath.base.quaternions.slerp`, :func:`~spatialmath.base.transforms2d.trinterp2`</span>
<span class="sd"> """</span>
<span class="n">s</span> <span class="o">=</span> <span class="n">argcheck</span><span class="o">.</span><span class="n">getvector</span><span class="p">(</span><span class="n">s</span><span class="p">)</span>
<span class="k">if</span> <span class="n">T0</span> <span class="ow">is</span> <span class="ow">not</span> <span class="kc">None</span><span class="p">:</span>
<span class="k">assert</span> <span class="nb">len</span><span class="p">(</span><span class="n">T0</span><span class="p">)</span> <span class="o">==</span> <span class="mi">1</span><span class="p">,</span> <span class="s1">'len(X0) must == 1'</span>
<span class="n">T0</span> <span class="o">=</span> <span class="n">T0</span><span class="o">.</span><span class="n">A</span>
<span class="k">if</span> <span class="bp">self</span><span class="o">.</span><span class="n">N</span> <span class="o">==</span> <span class="mi">2</span><span class="p">:</span>
<span class="k">if</span> <span class="nb">len</span><span class="p">(</span><span class="n">s</span><span class="p">)</span> <span class="o">></span> <span class="mi">1</span><span class="p">:</span>
<span class="k">assert</span> <span class="nb">len</span><span class="p">(</span><span class="bp">self</span><span class="p">)</span> <span class="o">==</span> <span class="mi">1</span><span class="p">,</span> <span class="s1">'if len(s) > 1, len(X) must == 1'</span>
<span class="k">return</span> <span class="bp">self</span><span class="o">.</span><span class="vm">__class__</span><span class="p">([</span><span class="n">tr</span><span class="o">.</span><span class="n">trinterp2</span><span class="p">(</span><span class="bp">self</span><span class="o">.</span><span class="n">A</span><span class="p">,</span> <span class="n">T0</span><span class="p">,</span> <span class="n">_s</span><span class="p">)</span> <span class="k">for</span> <span class="n">_s</span> <span class="ow">in</span> <span class="n">s</span><span class="p">])</span>
<span class="k">else</span><span class="p">:</span>
<span class="k">assert</span> <span class="nb">len</span><span class="p">(</span><span class="n">s</span><span class="p">)</span> <span class="o">==</span> <span class="mi">1</span><span class="p">,</span> <span class="s1">'if len(X) > 1, len(s) must == 1'</span>
<span class="k">return</span> <span class="bp">self</span><span class="o">.</span><span class="vm">__class__</span><span class="p">([</span><span class="n">tr</span><span class="o">.</span><span class="n">trinterp2</span><span class="p">(</span><span class="n">x</span><span class="p">,</span> <span class="n">T0</span><span class="p">,</span> <span class="n">s</span><span class="p">)</span> <span class="k">for</span> <span class="n">x</span> <span class="ow">in</span> <span class="bp">self</span><span class="o">.</span><span class="n">data</span><span class="p">])</span>
<span class="k">elif</span> <span class="bp">self</span><span class="o">.</span><span class="n">N</span> <span class="o">==</span> <span class="mi">3</span><span class="p">:</span>
<span class="k">if</span> <span class="nb">len</span><span class="p">(</span><span class="n">s</span><span class="p">)</span> <span class="o">></span> <span class="mi">1</span><span class="p">:</span>
<span class="k">assert</span> <span class="nb">len</span><span class="p">(</span><span class="bp">self</span><span class="p">)</span> <span class="o">==</span> <span class="mi">1</span><span class="p">,</span> <span class="s1">'if len(s) > 1, len(X) must == 1'</span>
<span class="k">return</span> <span class="bp">self</span><span class="o">.</span><span class="vm">__class__</span><span class="p">([</span><span class="n">tr</span><span class="o">.</span><span class="n">trinterp</span><span class="p">(</span><span class="bp">self</span><span class="o">.</span><span class="n">A</span><span class="p">,</span> <span class="n">T1</span><span class="o">=</span><span class="n">T0</span><span class="p">,</span> <span class="n">s</span><span class="o">=</span><span class="n">_s</span><span class="p">)</span> <span class="k">for</span> <span class="n">_s</span> <span class="ow">in</span> <span class="n">s</span><span class="p">])</span>
<span class="k">else</span><span class="p">:</span>
<span class="k">assert</span> <span class="nb">len</span><span class="p">(</span><span class="n">s</span><span class="p">)</span> <span class="o">==</span> <span class="mi">1</span><span class="p">,</span> <span class="s1">'if len(X) > 1, len(s) must == 1'</span>
<span class="k">return</span> <span class="bp">self</span><span class="o">.</span><span class="vm">__class__</span><span class="p">([</span><span class="n">tr</span><span class="o">.</span><span class="n">trinterp</span><span class="p">(</span><span class="n">x</span><span class="p">,</span> <span class="n">T1</span><span class="o">=</span><span class="n">T0</span><span class="p">,</span> <span class="n">s</span><span class="o">=</span><span class="n">s</span><span class="p">)</span> <span class="k">for</span> <span class="n">x</span> <span class="ow">in</span> <span class="bp">self</span><span class="o">.</span><span class="n">data</span><span class="p">])</span>
<span class="k">def</span> <span class="nf">norm</span><span class="p">(</span><span class="bp">self</span><span class="p">):</span>
<span class="sd">"""</span>
<span class="sd"> Normalize pose (superclass method)</span>
<span class="sd"> </span>
<span class="sd"> :return: pose</span>
<span class="sd"> :rtype: SO2, SE2, SO3, SE3 instance</span>
<span class="sd"> </span>
<span class="sd"> - ``X.norm()`` is an equivalent pose object but the rotational matrix </span>
<span class="sd"> part of all values has been adjusted to ensure it is a proper orthogonal</span>
<span class="sd"> matrix rotation.</span>
<span class="sd"> </span>
<span class="sd"> Example::</span>
<span class="sd"> </span>
<span class="sd"> >>> x = SE3()</span>
<span class="sd"> >>> y = x.norm()</span>
<span class="sd"> >>> y</span>
<span class="sd"> SE3(array([[1., 0., 0., 0.],</span>
<span class="sd"> [0., 1., 0., 0.],</span>
<span class="sd"> [0., 0., 1., 0.],</span>
<span class="sd"> [0., 0., 0., 1.]]))</span>
<span class="sd"> </span>
<span class="sd"> Notes:</span>
<span class="sd"> </span>
<span class="sd"> #. Only the direction of A vector (the z-axis) is unchanged.</span>
<span class="sd"> #. Used to prevent finite word length arithmetic causing transforms to </span>
<span class="sd"> become 'unnormalized'.</span>
<span class="sd"> </span>
<span class="sd"> :seealso: :func:`~spatialmath.base.transforms3d.trnorm`, :func:`~spatialmath.base.transforms2d.trnorm2`</span>
<span class="sd"> """</span>
<span class="k">if</span> <span class="bp">self</span><span class="o">.</span><span class="n">N</span> <span class="o">==</span> <span class="mi">2</span><span class="p">:</span>
<span class="k">return</span> <span class="bp">self</span><span class="o">.</span><span class="vm">__class__</span><span class="p">([</span><span class="n">tr</span><span class="o">.</span><span class="n">trnorm2</span><span class="p">(</span><span class="n">x</span><span class="p">)</span> <span class="k">for</span> <span class="n">x</span> <span class="ow">in</span> <span class="bp">self</span><span class="o">.</span><span class="n">data</span><span class="p">])</span>
<span class="k">else</span><span class="p">:</span>
<span class="k">return</span> <span class="bp">self</span><span class="o">.</span><span class="vm">__class__</span><span class="p">([</span><span class="n">tr</span><span class="o">.</span><span class="n">trnorm</span><span class="p">(</span><span class="n">x</span><span class="p">)</span> <span class="k">for</span> <span class="n">x</span> <span class="ow">in</span> <span class="bp">self</span><span class="o">.</span><span class="n">data</span><span class="p">])</span>
<span class="c1"># ----------------------- i/o stuff</span>
<span class="k">def</span> <span class="nf">printline</span><span class="p">(</span><span class="bp">self</span><span class="p">,</span> <span class="o">**</span><span class="n">kwargs</span><span class="p">):</span>
<span class="sd">"""</span>
<span class="sd"> Print pose as a single line (superclass method)</span>
<span class="sd"> </span>
<span class="sd"> :param label: text label to put at start of line</span>
<span class="sd"> :type label: str</span>
<span class="sd"> :param file: file to write formatted string to. [default, stdout]</span>
<span class="sd"> :type file: str</span>
<span class="sd"> :param fmt: conversion format for each number as used by ``format()``</span>
<span class="sd"> :type fmt: str</span>
<span class="sd"> :param unit: angular units: 'rad' [default], or 'deg'</span>
<span class="sd"> :type unit: str</span>
<span class="sd"> :return: optional formatted string</span>
<span class="sd"> :rtype: str</span>
<span class="sd"> </span>
<span class="sd"> For SO(3) or SE(3) also:</span>
<span class="sd"> </span>
<span class="sd"> :param orient: 3-angle convention to use</span>
<span class="sd"> :type orient: str</span>
<span class="sd"> </span>
<span class="sd"> - ``X.printline()`` print ``X`` in single-line format to ``stdout``, followed</span>
<span class="sd"> by a newline</span>
<span class="sd"> - ``X.printline(file=None)`` return a string containing ``X`` in </span>
<span class="sd"> single-line format</span>
<span class="sd"> </span>
<span class="sd"> Example::</span>
<span class="sd"> </span>
<span class="sd"> >>> x=SE3.Rx(0.3)</span>
<span class="sd"> >>> x.printline()</span>
<span class="sd"> t = 0, 0, 0; rpy/zyx = 17, 0, 0 deg</span>
<span class="sd"> </span>
<span class="sd"> """</span>
<span class="k">if</span> <span class="bp">self</span><span class="o">.</span><span class="n">N</span> <span class="o">==</span> <span class="mi">2</span><span class="p">:</span>
<span class="n">tr</span><span class="o">.</span><span class="n">trprint2</span><span class="p">(</span><span class="bp">self</span><span class="o">.</span><span class="n">A</span><span class="p">,</span> <span class="o">**</span><span class="n">kwargs</span><span class="p">)</span>
<span class="k">else</span><span class="p">:</span>
<span class="n">tr</span><span class="o">.</span><span class="n">trprint</span><span class="p">(</span><span class="bp">self</span><span class="o">.</span><span class="n">A</span><span class="p">,</span> <span class="o">**</span><span class="n">kwargs</span><span class="p">)</span>
<span class="k">def</span> <span class="fm">__repr__</span><span class="p">(</span><span class="bp">self</span><span class="p">):</span>
<span class="sd">"""</span>
<span class="sd"> Readable representation of pose (superclass method)</span>
<span class="sd"> </span>
<span class="sd"> :return: readable representation of the pose as a list of arrays</span>
<span class="sd"> :rtype: str</span>
<span class="sd"> </span>
<span class="sd"> Example::</span>
<span class="sd"> </span>
<span class="sd"> >>> x = SE3.Rx(0.3)</span>
<span class="sd"> >>> x</span>
<span class="sd"> SE3(array([[ 1. , 0. , 0. , 0. ],</span>
<span class="sd"> [ 0. , 0.95533649, -0.29552021, 0. ],</span>
<span class="sd"> [ 0. , 0.29552021, 0.95533649, 0. ],</span>
<span class="sd"> [ 0. , 0. , 0. , 1. ]]))</span>
<span class="sd"> """</span>
<span class="n">name</span> <span class="o">=</span> <span class="nb">type</span><span class="p">(</span><span class="bp">self</span><span class="p">)</span><span class="o">.</span><span class="vm">__name__</span>
<span class="k">if</span> <span class="nb">len</span><span class="p">(</span><span class="bp">self</span><span class="p">)</span> <span class="o">==</span> <span class="mi">0</span><span class="p">:</span>
<span class="k">return</span> <span class="n">name</span> <span class="o">+</span> <span class="s1">'([])'</span>
<span class="k">elif</span> <span class="nb">len</span><span class="p">(</span><span class="bp">self</span><span class="p">)</span> <span class="o">==</span> <span class="mi">1</span><span class="p">:</span>
<span class="c1"># need to indent subsequent lines of the native repr string by 4 spaces</span>
<span class="k">return</span> <span class="n">name</span> <span class="o">+</span> <span class="s1">'('</span> <span class="o">+</span> <span class="bp">self</span><span class="o">.</span><span class="n">A</span><span class="o">.</span><span class="fm">__repr__</span><span class="p">()</span><span class="o">.</span><span class="n">replace</span><span class="p">(</span><span class="s1">'</span><span class="se">\n</span><span class="s1">'</span><span class="p">,</span> <span class="s1">'</span><span class="se">\n</span><span class="s1"> '</span><span class="p">)</span> <span class="o">+</span> <span class="s1">')'</span>
<span class="k">else</span><span class="p">:</span>
<span class="c1"># format this as a list of ndarrays</span>
<span class="k">return</span> <span class="n">name</span> <span class="o">+</span> <span class="s1">'([</span><span class="se">\n</span><span class="s1">'</span> <span class="o">+</span> <span class="s1">',</span><span class="se">\n</span><span class="s1">'</span><span class="o">.</span><span class="n">join</span><span class="p">([</span><span class="n">v</span><span class="o">.</span><span class="fm">__repr__</span><span class="p">()</span> <span class="k">for</span> <span class="n">v</span> <span class="ow">in</span> <span class="bp">self</span><span class="o">.</span><span class="n">data</span><span class="p">])</span> <span class="o">+</span> <span class="s1">' ])'</span>
<span class="k">def</span> <span class="fm">__str__</span><span class="p">(</span><span class="bp">self</span><span class="p">):</span>
<span class="sd">"""</span>
<span class="sd"> Pretty string representation of pose (superclass method)</span>
<span class="sd"> :return: readable representation of the pose</span>
<span class="sd"> :rtype: str</span>
<span class="sd"> </span>
<span class="sd"> Convert the pose's matrix value to a simple grid of numbers.</span>
<span class="sd"> </span>
<span class="sd"> Example::</span>
<span class="sd"> </span>
<span class="sd"> >>> x = SE3.Rx(0.3)</span>
<span class="sd"> >>> print(x)</span>
<span class="sd"> 1 0 0 0 </span>
<span class="sd"> 0 0.955336 -0.29552 0 </span>
<span class="sd"> 0 0.29552 0.955336 0 </span>
<span class="sd"> 0 0 0 1 </span>
<span class="sd"> </span>
<span class="sd"> Notes:</span>
<span class="sd"> </span>
<span class="sd"> - By default, the output is colorised for an ANSI terminal console:</span>
<span class="sd"> </span>
<span class="sd"> * red: rotational elements</span>
<span class="sd"> * blue: translational elements</span>
<span class="sd"> * white: constant elements</span>
<span class="sd"> """</span>
<span class="k">return</span> <span class="bp">self</span><span class="o">.</span><span class="n">_string</span><span class="p">(</span><span class="n">color</span><span class="o">=</span><span class="kc">True</span><span class="p">)</span>
<span class="k">def</span> <span class="nf">_string</span><span class="p">(</span><span class="bp">self</span><span class="p">,</span> <span class="n">color</span><span class="o">=</span><span class="kc">False</span><span class="p">,</span> <span class="n">tol</span><span class="o">=</span><span class="mi">10</span><span class="p">):</span>
<span class="sd">"""</span>
<span class="sd"> Pretty print the matrix value</span>
<span class="sd"> </span>
<span class="sd"> :param color: colorise the output, defaults to False</span>
<span class="sd"> :type color: bool, optional</span>
<span class="sd"> :param tol: zero values smaller than tol*eps, defaults to 10</span>
<span class="sd"> :type tol: float, optional</span>
<span class="sd"> :return: multiline matrix representation</span>
<span class="sd"> :rtype: str</span>
<span class="sd"> </span>
<span class="sd"> Convert a matrix to a simple grid of numbers with optional</span>
<span class="sd"> colorization for an ANSI terminal console:</span>
<span class="sd"> </span>
<span class="sd"> * red: rotational elements</span>
<span class="sd"> * blue: translational elements</span>
<span class="sd"> * white: constant elements</span>
<span class="sd"> </span>
<span class="sd"> Example::</span>
<span class="sd"> </span>
<span class="sd"> >>> x = SE3.Rx(0.3)</span>
<span class="sd"> >>> print(str(x))</span>
<span class="sd"> 1 0 0 0 </span>
<span class="sd"> 0 0.955336 -0.29552 0 </span>
<span class="sd"> 0 0.29552 0.955336 0 </span>
<span class="sd"> 0 0 0 1 </span>
<span class="sd"> """</span>
<span class="c1">#print('in __str__')</span>
<span class="n">FG</span> <span class="o">=</span> <span class="k">lambda</span> <span class="n">c</span><span class="p">:</span> <span class="n">fg</span><span class="p">(</span><span class="n">c</span><span class="p">)</span> <span class="k">if</span> <span class="n">_color</span> <span class="k">else</span> <span class="s1">''</span>
<span class="n">BG</span> <span class="o">=</span> <span class="k">lambda</span> <span class="n">c</span><span class="p">:</span> <span class="n">bg</span><span class="p">(</span><span class="n">c</span><span class="p">)</span> <span class="k">if</span> <span class="n">_color</span> <span class="k">else</span> <span class="s1">''</span>
<span class="n">ATTR</span> <span class="o">=</span> <span class="k">lambda</span> <span class="n">c</span><span class="p">:</span> <span class="n">attr</span><span class="p">(</span><span class="n">c</span><span class="p">)</span> <span class="k">if</span> <span class="n">_color</span> <span class="k">else</span> <span class="s1">''</span>
<span class="k">def</span> <span class="nf">mformat</span><span class="p">(</span><span class="bp">self</span><span class="p">,</span> <span class="n">X</span><span class="p">):</span>
<span class="c1"># X is an ndarray value to be display</span>
<span class="c1"># self provides set type for formatting</span>
<span class="n">out</span> <span class="o">=</span> <span class="s1">''</span>
<span class="n">n</span> <span class="o">=</span> <span class="bp">self</span><span class="o">.</span><span class="n">N</span> <span class="c1"># dimension of rotation submatrix</span>
<span class="k">for</span> <span class="n">rownum</span><span class="p">,</span> <span class="n">row</span> <span class="ow">in</span> <span class="nb">enumerate</span><span class="p">(</span><span class="n">X</span><span class="p">):</span>
<span class="n">rowstr</span> <span class="o">=</span> <span class="s1">' '</span>
<span class="c1"># format the columns</span>
<span class="k">for</span> <span class="n">colnum</span><span class="p">,</span> <span class="n">element</span> <span class="ow">in</span> <span class="nb">enumerate</span><span class="p">(</span><span class="n">row</span><span class="p">):</span>
<span class="k">if</span> <span class="nb">isinstance</span><span class="p">(</span><span class="n">element</span><span class="p">,</span> <span class="n">sympy</span><span class="o">.</span><span class="n">Expr</span><span class="p">):</span>
<span class="n">s</span> <span class="o">=</span> <span class="s1">'</span><span class="si">{:<12s}</span><span class="s1">'</span><span class="o">.</span><span class="n">format</span><span class="p">(</span><span class="nb">str</span><span class="p">(</span><span class="n">element</span><span class="p">))</span>
<span class="k">else</span><span class="p">:</span>
<span class="k">if</span> <span class="n">tol</span> <span class="o">></span> <span class="mi">0</span> <span class="ow">and</span> <span class="nb">abs</span><span class="p">(</span><span class="n">element</span><span class="p">)</span> <span class="o"><</span> <span class="n">tol</span> <span class="o">*</span> <span class="n">_eps</span><span class="p">:</span>
<span class="n">element</span> <span class="o">=</span> <span class="mi">0</span>
<span class="n">s</span> <span class="o">=</span> <span class="s1">'</span><span class="si">{:< 12g}</span><span class="s1">'</span><span class="o">.</span><span class="n">format</span><span class="p">(</span><span class="n">element</span><span class="p">)</span>
<span class="k">if</span> <span class="n">rownum</span> <span class="o"><</span> <span class="n">n</span><span class="p">:</span>
<span class="k">if</span> <span class="n">colnum</span> <span class="o"><</span> <span class="n">n</span><span class="p">:</span>
<span class="c1"># rotation part</span>
<span class="n">s</span> <span class="o">=</span> <span class="n">FG</span><span class="p">(</span><span class="s1">'red'</span><span class="p">)</span> <span class="o">+</span> <span class="n">BG</span><span class="p">(</span><span class="s1">'grey_93'</span><span class="p">)</span> <span class="o">+</span> <span class="n">s</span> <span class="o">+</span> <span class="n">ATTR</span><span class="p">(</span><span class="mi">0</span><span class="p">)</span>
<span class="k">else</span><span class="p">:</span>
<span class="c1"># translation part</span>
<span class="n">s</span> <span class="o">=</span> <span class="n">FG</span><span class="p">(</span><span class="s1">'blue'</span><span class="p">)</span> <span class="o">+</span> <span class="n">BG</span><span class="p">(</span><span class="s1">'grey_93'</span><span class="p">)</span> <span class="o">+</span> <span class="n">s</span> <span class="o">+</span> <span class="n">ATTR</span><span class="p">(</span><span class="mi">0</span><span class="p">)</span>
<span class="k">else</span><span class="p">:</span>
<span class="c1"># bottom row</span>
<span class="n">s</span> <span class="o">=</span> <span class="n">FG</span><span class="p">(</span><span class="s1">'grey_50'</span><span class="p">)</span> <span class="o">+</span> <span class="n">BG</span><span class="p">(</span><span class="s1">'grey_93'</span><span class="p">)</span> <span class="o">+</span> <span class="n">s</span> <span class="o">+</span> <span class="n">ATTR</span><span class="p">(</span><span class="mi">0</span><span class="p">)</span>
<span class="n">rowstr</span> <span class="o">+=</span> <span class="n">s</span>
<span class="n">out</span> <span class="o">+=</span> <span class="n">rowstr</span> <span class="o">+</span> <span class="n">BG</span><span class="p">(</span><span class="s1">'grey_93'</span><span class="p">)</span> <span class="o">+</span> <span class="s1">' '</span> <span class="o">+</span> <span class="n">ATTR</span><span class="p">(</span><span class="mi">0</span><span class="p">)</span> <span class="o">+</span> <span class="s1">'</span><span class="se">\n</span><span class="s1">'</span>
<span class="k">return</span> <span class="n">out</span>
<span class="n">output_str</span> <span class="o">=</span> <span class="s1">''</span>
<span class="k">if</span> <span class="nb">len</span><span class="p">(</span><span class="bp">self</span><span class="o">.</span><span class="n">data</span><span class="p">)</span> <span class="o">==</span> <span class="mi">0</span><span class="p">:</span>
<span class="n">output_str</span> <span class="o">=</span> <span class="s1">'[]'</span>
<span class="k">elif</span> <span class="nb">len</span><span class="p">(</span><span class="bp">self</span><span class="o">.</span><span class="n">data</span><span class="p">)</span> <span class="o">==</span> <span class="mi">1</span><span class="p">:</span>
<span class="c1"># single matrix case</span>
<span class="n">output_str</span> <span class="o">=</span> <span class="n">mformat</span><span class="p">(</span><span class="bp">self</span><span class="p">,</span> <span class="bp">self</span><span class="o">.</span><span class="n">A</span><span class="p">)</span>
<span class="k">else</span><span class="p">:</span>
<span class="c1"># sequence case</span>
<span class="k">for</span> <span class="n">count</span><span class="p">,</span> <span class="n">X</span> <span class="ow">in</span> <span class="nb">enumerate</span><span class="p">(</span><span class="bp">self</span><span class="o">.</span><span class="n">data</span><span class="p">):</span>
<span class="c1"># add separator lines and the index</span>
<span class="n">output_str</span> <span class="o">+=</span> <span class="n">fg</span><span class="p">(</span><span class="s1">'green'</span><span class="p">)</span> <span class="o">+</span> <span class="s1">'[</span><span class="si">{:d}</span><span class="s1">] =</span><span class="se">\n</span><span class="s1">'</span><span class="o">.</span><span class="n">format</span><span class="p">(</span><span class="n">count</span><span class="p">)</span> <span class="o">+</span> <span class="n">attr</span><span class="p">(</span><span class="mi">0</span><span class="p">)</span> <span class="o">+</span> <span class="n">mformat</span><span class="p">(</span><span class="bp">self</span><span class="p">,</span> <span class="n">X</span><span class="p">)</span>
<span class="k">return</span> <span class="n">output_str</span>
<span class="c1"># ----------------------- graphics</span>
<span class="k">def</span> <span class="nf">plot</span><span class="p">(</span><span class="bp">self</span><span class="p">,</span> <span class="o">*</span><span class="n">args</span><span class="p">,</span> <span class="o">**</span><span class="n">kwargs</span><span class="p">):</span>
<span class="sd">"""</span>
<span class="sd"> Plot pose object as a coordinate frame (superclass method)</span>
<span class="sd"> </span>
<span class="sd"> :param `**kwargs`: plotting options</span>
<span class="sd"> </span>
<span class="sd"> - ``X.plot()`` displays the pose ``X`` as a coordinate frame in either</span>
<span class="sd"> 2D or 3D axes. There are many options, see the links below.</span>
<span class="sd"> Example::</span>
<span class="sd"> </span>
<span class="sd"> >>> X = SE3.Rx(0.3)</span>
<span class="sd"> >>> X.plot(frame='A', color='green')</span>
<span class="sd"> </span>
<span class="sd"> :seealso: :func:`~spatialmath.base.transforms3d.trplot`, :func:`~spatialmath.base.transforms2d.trplot2`</span>
<span class="sd"> """</span>
<span class="k">if</span> <span class="bp">self</span><span class="o">.</span><span class="n">N</span> <span class="o">==</span> <span class="mi">2</span><span class="p">:</span>
<span class="n">tr</span><span class="o">.</span><span class="n">trplot2</span><span class="p">(</span><span class="bp">self</span><span class="o">.</span><span class="n">A</span><span class="p">,</span> <span class="o">*</span><span class="n">args</span><span class="p">,</span> <span class="o">**</span><span class="n">kwargs</span><span class="p">)</span>
<span class="k">else</span><span class="p">:</span>
<span class="n">tr</span><span class="o">.</span><span class="n">trplot</span><span class="p">(</span><span class="bp">self</span><span class="o">.</span><span class="n">A</span><span class="p">,</span> <span class="o">*</span><span class="n">args</span><span class="p">,</span> <span class="o">**</span><span class="n">kwargs</span><span class="p">)</span>
<span class="k">def</span> <span class="nf">animate</span><span class="p">(</span><span class="bp">self</span><span class="p">,</span> <span class="o">*</span><span class="n">args</span><span class="p">,</span> <span class="n">T0</span><span class="o">=</span><span class="kc">None</span><span class="p">,</span> <span class="o">**</span><span class="n">kwargs</span><span class="p">):</span>
<span class="sd">"""</span>
<span class="sd"> Plot pose object as an animated coordinate frame (superclass method)</span>
<span class="sd"> </span>
<span class="sd"> :param `**kwargs`: plotting options</span>
<span class="sd"> </span>
<span class="sd"> - ``X.plot()`` displays the pose ``X`` as a coordinate frame moving</span>
<span class="sd"> from the origin, or ``T0``, in either 2D or 3D axes. There are </span>
<span class="sd"> many options, see the links below.</span>
<span class="sd"> Example::</span>
<span class="sd"> </span>
<span class="sd"> >>> X = SE3.Rx(0.3)</span>
<span class="sd"> >>> X.animate(frame='A', color='green')</span>
<span class="sd"> :seealso: :func:`~spatialmath.base.transforms3d.tranimate`, :func:`~spatialmath.base.transforms2d.tranimate2`</span>
<span class="sd"> """</span>
<span class="k">if</span> <span class="n">T0</span> <span class="ow">is</span> <span class="ow">not</span> <span class="kc">None</span><span class="p">:</span>
<span class="n">T0</span> <span class="o">=</span> <span class="n">T0</span><span class="o">.</span><span class="n">A</span>
<span class="k">if</span> <span class="bp">self</span><span class="o">.</span><span class="n">N</span> <span class="o">==</span> <span class="mi">2</span><span class="p">:</span>
<span class="n">tr</span><span class="o">.</span><span class="n">tranimate2</span><span class="p">(</span><span class="bp">self</span><span class="o">.</span><span class="n">A</span><span class="p">,</span> <span class="n">T0</span><span class="o">=</span><span class="n">T0</span><span class="p">,</span> <span class="o">*</span><span class="n">args</span><span class="p">,</span> <span class="o">**</span><span class="n">kwargs</span><span class="p">)</span>
<span class="k">else</span><span class="p">:</span>
<span class="n">tr</span><span class="o">.</span><span class="n">tranimate</span><span class="p">(</span><span class="bp">self</span><span class="o">.</span><span class="n">A</span><span class="p">,</span> <span class="n">T0</span><span class="o">=</span><span class="n">T0</span><span class="p">,</span> <span class="o">*</span><span class="n">args</span><span class="p">,</span> <span class="o">**</span><span class="n">kwargs</span><span class="p">)</span>
<span class="c1"># ------------------------------------------------------------------------ #</span>
<span class="c1">#----------------------- arithmetic</span>
<span class="k">def</span> <span class="fm">__mul__</span><span class="p">(</span><span class="n">left</span><span class="p">,</span> <span class="n">right</span><span class="p">):</span>
<span class="sd">"""</span>
<span class="sd"> Overloaded ``*`` operator (superclass method)</span>
<span class="sd"> :arg left: left multiplicand</span>
<span class="sd"> :arg right: right multiplicand</span>
<span class="sd"> :return: product</span>
<span class="sd"> :raises: ValueError</span>
<span class="sd"> Pose composition, scaling or vector transformation:</span>
<span class="sd"> </span>
<span class="sd"> - ``X * Y`` compounds the poses ``X`` and ``Y``</span>
<span class="sd"> - ``X * s`` performs elementwise multiplication of the elements of ``X`` by ``s``</span>
<span class="sd"> - ``s * X`` performs elementwise multiplication of the elements of ``X`` by ``s``</span>
<span class="sd"> - ``X * v`` linear transform of the vector ``v``</span>
<span class="sd"> ============== ============== =========== ======================</span>
<span class="sd"> Multiplicands Product</span>
<span class="sd"> ------------------------------- -----------------------------------</span>
<span class="sd"> left right type operation</span>
<span class="sd"> ============== ============== =========== ======================</span>
<span class="sd"> Pose Pose Pose matrix product</span>
<span class="sd"> Pose scalar NxN matrix element-wise product</span>
<span class="sd"> scalar Pose NxN matrix element-wise product</span>
<span class="sd"> Pose N-vector N-vector vector transform</span>
<span class="sd"> Pose NxM matrix NxM matrix transform each column</span>
<span class="sd"> ============== ============== =========== ======================</span>
<span class="sd"> </span>
<span class="sd"> Notes:</span>
<span class="sd"> </span>
<span class="sd"> #. Pose is ``SO2``, ``SE2``, ``SO3`` or ``SE3`` instance</span>
<span class="sd"> #. N is 2 for ``SO2``, ``SE2``; 3 for ``SO3`` or ``SE3``</span>