-
Notifications
You must be signed in to change notification settings - Fork 91
/
Copy pathfunc_2d.html
1235 lines (1193 loc) · 110 KB
/
func_2d.html
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 class="writer-html5" lang="en">
<head>
<meta charset="utf-8" /><meta name="viewport" content="width=device-width, initial-scale=1" />
<link rel="icon" sizes="16x16" href="_static/favicon-16x16.png" type="image/png">
<link rel="icon" sizes="32x32" href="_static/favicon-32x32.png" type="image/png">
<link rel="apple-touch-icon" sizes="180x180" href="_static/apple-touch-icon.png" type="image/png">
<link rel="android-chrome" sizes="192x192" href="_static/android-chrome-192x192.png" type="image/png">
<link rel="android-chrome" sizes="512x512" href="_static/android-chrome-512x512.png" type="image/png">
<meta name="viewport" content="width=device-width, initial-scale=1.0" />
<title>Transforms in 2D — Spatial Maths package documentation</title>
<link rel="stylesheet" type="text/css" href="_static/pygments.css?v=b86133f3" />
<link rel="stylesheet" type="text/css" href="_static/css/theme.css?v=e59714d7" />
<link rel="stylesheet" type="text/css" href="_static/graphviz.css?v=eafc0fe6" />
<link rel="stylesheet" type="text/css" href="_static/plot_directive.css" />
<script src="_static/jquery.js?v=5d32c60e"></script>
<script src="_static/_sphinx_javascript_frameworks_compat.js?v=2cd50e6c"></script>
<script data-url_root="./" id="documentation_options" src="_static/documentation_options.js?v=b3ba4146"></script>
<script src="_static/doctools.js?v=888ff710"></script>
<script src="_static/sphinx_highlight.js?v=4825356b"></script>
<script>window.MathJax = {"tex": {"macros": {"presup": ["\\,{}^{\\scriptscriptstyle #1}\\!", 1], "SE": ["\\mathbf{SE}(#1)", 1], "SO": ["\\mathbf{SO}(#1)", 1], "se": ["\\mathbf{se}(#1)", 1], "so": ["\\mathbf{so}(#1)", 1], "vec": ["\\boldsymbol{#1}", 1], "dvec": ["\\dot{\\boldsymbol{#1}}", 1], "ddvec": ["\\ddot{\\boldsymbol{#1}}", 1], "fvec": ["\\presup{#1}\\boldsymbol{#2}", 2], "fdvec": ["\\presup{#1}\\dot{\\boldsymbol{#2}}", 2], "fddvec": ["\\presup{#1}\\ddot{\\boldsymbol{#2}}", 2], "norm": ["\\Vert #1 \\Vert", 1], "mat": ["\\mathbf{#1}", 1], "dmat": ["\\dot{\\mathbf{#1}}", 1], "fmat": ["\\presup{#1}\\mathbf{#2}", 2], "sk": ["\\left[#1\\right]", 1], "skx": ["\\left[#1\\right]_{\\times}", 1], "vex": ["\\vee\\left( #1\\right)", 1], "vexx": ["\\vee_{\\times}\\left( #1\\right)", 1], "q": "\\mathring{q}", "fq": ["\\presup{#1}\\mathring{q}", 1]}}}</script>
<script defer="defer" src="https://cdn.jsdelivr.net/npm/mathjax@3/es5/tex-mml-chtml.js"></script>
<script src="_static/js/theme.js"></script>
<link rel="index" title="Index" href="genindex.html" />
<link rel="search" title="Search" href="search.html" />
<link rel="next" title="Transforms in 3D" href="func_3d.html" />
<link rel="prev" title="Function reference" href="functions.html" />
</head>
<body class="wy-body-for-nav">
<div class="wy-grid-for-nav">
<nav data-toggle="wy-nav-shift" class="wy-nav-side">
<div class="wy-side-scroll">
<div class="wy-side-nav-search" >
<a href="index.html" class="icon icon-home">
Spatial Maths package
<img src="_static/CartesianSnakes_LogoW.png" class="logo" alt="Logo"/>
</a>
<div role="search">
<form id="rtd-search-form" class="wy-form" action="search.html" method="get">
<input type="text" name="q" placeholder="Search docs" aria-label="Search docs" />
<input type="hidden" name="check_keywords" value="yes" />
<input type="hidden" name="area" value="default" />
</form>
</div>
</div><div class="wy-menu wy-menu-vertical" data-spy="affix" role="navigation" aria-label="Navigation menu">
<ul class="current">
<li class="toctree-l1"><a class="reference internal" href="intro.html">Introduction</a></li>
<li class="toctree-l1"><a class="reference internal" href="spatialmath.html">Class reference</a></li>
<li class="toctree-l1 current"><a class="reference internal" href="functions.html">Function reference</a><ul class="current">
<li class="toctree-l2 current"><a class="current reference internal" href="#">Transforms in 2D</a><ul>
<li class="toctree-l3"><a class="reference internal" href="#spatialmath.base.transforms2d.ICP2d"><code class="docutils literal notranslate"><span class="pre">ICP2d()</span></code></a></li>
<li class="toctree-l3"><a class="reference internal" href="#spatialmath.base.transforms2d.ishom2"><code class="docutils literal notranslate"><span class="pre">ishom2()</span></code></a></li>
<li class="toctree-l3"><a class="reference internal" href="#spatialmath.base.transforms2d.isrot2"><code class="docutils literal notranslate"><span class="pre">isrot2()</span></code></a></li>
<li class="toctree-l3"><a class="reference internal" href="#spatialmath.base.transforms2d.points2tr2"><code class="docutils literal notranslate"><span class="pre">points2tr2()</span></code></a></li>
<li class="toctree-l3"><a class="reference internal" href="#spatialmath.base.transforms2d.pos2tr2"><code class="docutils literal notranslate"><span class="pre">pos2tr2()</span></code></a></li>
<li class="toctree-l3"><a class="reference internal" href="#spatialmath.base.transforms2d.rot2"><code class="docutils literal notranslate"><span class="pre">rot2()</span></code></a></li>
<li class="toctree-l3"><a class="reference internal" href="#spatialmath.base.transforms2d.tr2jac2"><code class="docutils literal notranslate"><span class="pre">tr2jac2()</span></code></a></li>
<li class="toctree-l3"><a class="reference internal" href="#spatialmath.base.transforms2d.tr2pos2"><code class="docutils literal notranslate"><span class="pre">tr2pos2()</span></code></a></li>
<li class="toctree-l3"><a class="reference internal" href="#spatialmath.base.transforms2d.tr2xyt"><code class="docutils literal notranslate"><span class="pre">tr2xyt()</span></code></a></li>
<li class="toctree-l3"><a class="reference internal" href="#spatialmath.base.transforms2d.tradjoint2"><code class="docutils literal notranslate"><span class="pre">tradjoint2()</span></code></a></li>
<li class="toctree-l3"><a class="reference internal" href="#spatialmath.base.transforms2d.tranimate2"><code class="docutils literal notranslate"><span class="pre">tranimate2()</span></code></a></li>
<li class="toctree-l3"><a class="reference internal" href="#spatialmath.base.transforms2d.transl2"><code class="docutils literal notranslate"><span class="pre">transl2()</span></code></a></li>
<li class="toctree-l3"><a class="reference internal" href="#spatialmath.base.transforms2d.trexp2"><code class="docutils literal notranslate"><span class="pre">trexp2()</span></code></a></li>
<li class="toctree-l3"><a class="reference internal" href="#spatialmath.base.transforms2d.trinterp2"><code class="docutils literal notranslate"><span class="pre">trinterp2()</span></code></a></li>
<li class="toctree-l3"><a class="reference internal" href="#spatialmath.base.transforms2d.trinv2"><code class="docutils literal notranslate"><span class="pre">trinv2()</span></code></a></li>
<li class="toctree-l3"><a class="reference internal" href="#spatialmath.base.transforms2d.trlog2"><code class="docutils literal notranslate"><span class="pre">trlog2()</span></code></a></li>
<li class="toctree-l3"><a class="reference internal" href="#spatialmath.base.transforms2d.trnorm2"><code class="docutils literal notranslate"><span class="pre">trnorm2()</span></code></a></li>
<li class="toctree-l3"><a class="reference internal" href="#spatialmath.base.transforms2d.trot2"><code class="docutils literal notranslate"><span class="pre">trot2()</span></code></a></li>
<li class="toctree-l3"><a class="reference internal" href="#spatialmath.base.transforms2d.trplot2"><code class="docutils literal notranslate"><span class="pre">trplot2()</span></code></a></li>
<li class="toctree-l3"><a class="reference internal" href="#spatialmath.base.transforms2d.trprint2"><code class="docutils literal notranslate"><span class="pre">trprint2()</span></code></a></li>
<li class="toctree-l3"><a class="reference internal" href="#spatialmath.base.transforms2d.xyt2tr"><code class="docutils literal notranslate"><span class="pre">xyt2tr()</span></code></a></li>
</ul>
</li>
<li class="toctree-l2"><a class="reference internal" href="func_3d.html">Transforms in 3D</a></li>
<li class="toctree-l2"><a class="reference internal" href="func_nd.html">Transforms in ND</a></li>
<li class="toctree-l2"><a class="reference internal" href="func_quat.html">Quaternions</a></li>
<li class="toctree-l2"><a class="reference internal" href="func_symbolic.html">Symbolic computation</a></li>
<li class="toctree-l2"><a class="reference internal" href="func_vector.html">Vectors</a></li>
<li class="toctree-l2"><a class="reference internal" href="func_graphics.html">Graphics and animation</a></li>
<li class="toctree-l2"><a class="reference internal" href="func_args.html">Argument checking</a></li>
<li class="toctree-l2"><a class="reference internal" href="func_numeric.html">Numerical utility functions</a></li>
</ul>
</li>
<li class="toctree-l1"><a class="reference internal" href="indices.html">Indices</a></li>
</ul>
</div>
</div>
</nav>
<section data-toggle="wy-nav-shift" class="wy-nav-content-wrap"><nav class="wy-nav-top" aria-label="Mobile navigation menu" >
<i data-toggle="wy-nav-top" class="fa fa-bars"></i>
<a href="index.html">Spatial Maths package</a>
</nav>
<div class="wy-nav-content">
<div class="rst-content">
<div role="navigation" aria-label="Page navigation">
<ul class="wy-breadcrumbs">
<li><a href="index.html" class="icon icon-home" aria-label="Home"></a></li>
<li class="breadcrumb-item"><a href="functions.html">Function reference</a></li>
<li class="breadcrumb-item active">Transforms in 2D</li>
<li class="wy-breadcrumbs-aside">
<a href="_sources/func_2d.rst.txt" rel="nofollow"> View page source</a>
</li>
</ul><div class="rst-breadcrumbs-buttons" role="navigation" aria-label="Sequential page navigation">
<a href="functions.html" class="btn btn-neutral float-left" title="Function reference" accesskey="p"><span class="fa fa-arrow-circle-left" aria-hidden="true"></span> Previous</a>
<a href="func_3d.html" class="btn btn-neutral float-right" title="Transforms in 3D" accesskey="n">Next <span class="fa fa-arrow-circle-right" aria-hidden="true"></span></a>
</div>
<hr/>
</div>
<div role="main" class="document" itemscope="itemscope" itemtype="http://schema.org/Article">
<div itemprop="articleBody">
<section id="module-spatialmath.base.transforms2d">
<span id="transforms-in-2d"></span><h1>Transforms in 2D<a class="headerlink" href="#module-spatialmath.base.transforms2d" title="Permalink to this heading"></a></h1>
<p>These functions create and manipulate 2D rotation matrices and rigid-body
transformations as 2x2 SO(2) matrices and 3x3 SE(2) matrices respectively.
These matrices are represented as 2D NumPy arrays.</p>
<p>Vector arguments are what numpy refers to as <code class="docutils literal notranslate"><span class="pre">array_like</span></code> and can be a list,
tuple, numpy array, numpy row vector or numpy column vector.</p>
<dl class="py function">
<dt class="sig sig-object py" id="spatialmath.base.transforms2d.ICP2d">
<span class="sig-name descname"><span class="pre">ICP2d</span></span><span class="sig-paren">(</span><em class="sig-param"><span class="n"><span class="pre">reference</span></span></em>, <em class="sig-param"><span class="n"><span class="pre">source</span></span></em>, <em class="sig-param"><span class="n"><span class="pre">T</span></span><span class="o"><span class="pre">=</span></span><span class="default_value"><span class="pre">None</span></span></em>, <em class="sig-param"><span class="n"><span class="pre">max_iter</span></span><span class="o"><span class="pre">=</span></span><span class="default_value"><span class="pre">20</span></span></em>, <em class="sig-param"><span class="n"><span class="pre">min_delta_err</span></span><span class="o"><span class="pre">=</span></span><span class="default_value"><span class="pre">0.0001</span></span></em><span class="sig-paren">)</span><a class="reference internal" href="_modules/spatialmath/base/transforms2d.html#ICP2d"><span class="viewcode-link"><span class="pre">[source]</span></span></a><a class="headerlink" href="#spatialmath.base.transforms2d.ICP2d" title="Permalink to this definition"></a></dt>
<dd><p>Iterated closest point (ICP) in 2D</p>
<dl class="field-list simple">
<dt class="field-odd">Parameters<span class="colon">:</span></dt>
<dd class="field-odd"><ul class="simple">
<li><p><strong>reference</strong> (<em>ndarray</em><em>(</em><em>2</em><em>,</em><em>N</em><em>)</em>) – points (columns) to which the source points are to be aligned</p></li>
<li><p><strong>source</strong> (<em>ndarray</em><em>(</em><em>2</em><em>,</em><em>M</em><em>)</em>) – points (columns) to align to the reference set of points</p></li>
<li><p><strong>T</strong> (<em>ndarray</em><em>(</em><em>3</em><em>,</em><em>3</em><em>)</em><em>, </em><em>optional</em>) – initial pose , defaults to None</p></li>
<li><p><strong>max_iter</strong> (<em>int</em><em>, </em><em>optional</em>) – max number of iterations, defaults to 20</p></li>
<li><p><strong>min_delta_err</strong> (<em>float</em><em>, </em><em>optional</em>) – min_delta_err, defaults to 1e-4</p></li>
</ul>
</dd>
<dt class="field-even">Returns<span class="colon">:</span></dt>
<dd class="field-even"><p>pose of source point cloud relative to the reference point cloud</p>
</dd>
<dt class="field-odd">Return type<span class="colon">:</span></dt>
<dd class="field-odd"><p>SE2Array</p>
</dd>
</dl>
<p>Uses the iterative closest point algorithm to find the transformation that
transforms the source point cloud to align with the reference point cloud, which
minimizes the sum of squared errors between nearest neighbors in the two point
clouds.</p>
<div class="admonition note">
<p class="admonition-title">Note</p>
<p>Point correspondence is not required and the two point clouds do not have
to have the same number of points.</p>
</div>
<div class="admonition warning">
<p class="admonition-title">Warning</p>
<p>The point cloud argument order is reversed compared to <code class="xref py py-func docutils literal notranslate"><span class="pre">points2tr()</span></code>.</p>
</div>
<dl class="field-list simple">
<dt class="field-odd">Seealso<span class="colon">:</span></dt>
<dd class="field-odd"><p><code class="xref py py-func docutils literal notranslate"><span class="pre">points2tr()</span></code></p>
</dd>
</dl>
</dd></dl>
<dl class="py function">
<dt class="sig sig-object py" id="spatialmath.base.transforms2d.ishom2">
<span class="sig-name descname"><span class="pre">ishom2</span></span><span class="sig-paren">(</span><em class="sig-param"><span class="n"><span class="pre">T</span></span></em>, <em class="sig-param"><span class="n"><span class="pre">check</span></span><span class="o"><span class="pre">=</span></span><span class="default_value"><span class="pre">False</span></span></em>, <em class="sig-param"><span class="n"><span class="pre">tol</span></span><span class="o"><span class="pre">=</span></span><span class="default_value"><span class="pre">20</span></span></em><span class="sig-paren">)</span><a class="reference internal" href="_modules/spatialmath/base/transforms2d.html#ishom2"><span class="viewcode-link"><span class="pre">[source]</span></span></a><a class="headerlink" href="#spatialmath.base.transforms2d.ishom2" title="Permalink to this definition"></a></dt>
<dd><p>Test if matrix belongs to SE(2)</p>
<dl class="field-list simple">
<dt class="field-odd">Parameters<span class="colon">:</span></dt>
<dd class="field-odd"><ul class="simple">
<li><p><strong>T</strong> (<em>ndarray</em><em>(</em><em>3</em><em>,</em><em>3</em><em>)</em>) – SE(2) matrix to test</p></li>
<li><p><strong>check</strong> (<em>bool</em>) – check validity of rotation submatrix</p></li>
<li><p><strong>tol</strong> (<span class="sphinx_autodoc_typehints-type"><code class="xref py py-class docutils literal notranslate"><span class="pre">float</span></code></span>) – Tolerance in units of eps for zero-rotation case, defaults to 20</p></li>
</ul>
</dd>
<dt class="field-even">Type<span class="colon">:</span></dt>
<dd class="field-even"><p>float</p>
</dd>
<dt class="field-odd">Returns<span class="colon">:</span></dt>
<dd class="field-odd"><p>whether matrix is an SE(2) homogeneous transformation matrix</p>
</dd>
<dt class="field-even">Return type<span class="colon">:</span></dt>
<dd class="field-even"><p>bool</p>
</dd>
</dl>
<ul class="simple">
<li><p><code class="docutils literal notranslate"><span class="pre">ishom2(T)</span></code> is True if the argument <code class="docutils literal notranslate"><span class="pre">T</span></code> is of dimension 3x3</p></li>
<li><p><code class="docutils literal notranslate"><span class="pre">ishom2(T,</span> <span class="pre">check=True)</span></code> as above, but also checks orthogonality of the
rotation sub-matrix and validitity of the bottom row.</p></li>
</ul>
<div class="highlight-pycon notranslate"><div class="highlight"><pre><span></span><span class="gp">>>> </span><span class="kn">from</span><span class="w"> </span><span class="nn">spatialmath.base</span><span class="w"> </span><span class="kn">import</span> <span class="o">*</span>
<span class="gp">>>> </span><span class="kn">import</span><span class="w"> </span><span class="nn">numpy</span><span class="w"> </span><span class="k">as</span><span class="w"> </span><span class="nn">np</span>
<span class="gp">>>> </span><span class="n">T</span> <span class="o">=</span> <span class="n">np</span><span class="o">.</span><span class="n">array</span><span class="p">([[</span><span class="mi">1</span><span class="p">,</span> <span class="mi">0</span><span class="p">,</span> <span class="mi">3</span><span class="p">],</span> <span class="p">[</span><span class="mi">0</span><span class="p">,</span> <span class="mi">1</span><span class="p">,</span> <span class="mi">4</span><span class="p">],</span> <span class="p">[</span><span class="mi">0</span><span class="p">,</span> <span class="mi">0</span><span class="p">,</span> <span class="mi">1</span><span class="p">]])</span>
<span class="gp">>>> </span><span class="n">ishom2</span><span class="p">(</span><span class="n">T</span><span class="p">)</span>
<span class="go">True</span>
<span class="gp">>>> </span><span class="n">T</span> <span class="o">=</span> <span class="n">np</span><span class="o">.</span><span class="n">array</span><span class="p">([[</span><span class="mi">1</span><span class="p">,</span> <span class="mi">1</span><span class="p">,</span> <span class="mi">3</span><span class="p">],</span> <span class="p">[</span><span class="mi">0</span><span class="p">,</span> <span class="mi">1</span><span class="p">,</span> <span class="mi">4</span><span class="p">],</span> <span class="p">[</span><span class="mi">0</span><span class="p">,</span> <span class="mi">0</span><span class="p">,</span> <span class="mi">1</span><span class="p">]])</span> <span class="c1"># invalid SE(2)</span>
<span class="gp">>>> </span><span class="n">ishom2</span><span class="p">(</span><span class="n">T</span><span class="p">)</span> <span class="c1"># a quick check says it is an SE(2)</span>
<span class="go">True</span>
<span class="gp">>>> </span><span class="n">ishom2</span><span class="p">(</span><span class="n">T</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="c1"># but if we check more carefully...</span>
<span class="go">False</span>
<span class="gp">>>> </span><span class="n">R</span> <span class="o">=</span> <span class="n">np</span><span class="o">.</span><span class="n">array</span><span class="p">([[</span><span class="mi">1</span><span class="p">,</span> <span class="mi">0</span><span class="p">],</span> <span class="p">[</span><span class="mi">0</span><span class="p">,</span> <span class="mi">1</span><span class="p">]])</span>
<span class="gp">>>> </span><span class="n">ishom2</span><span class="p">(</span><span class="n">R</span><span class="p">)</span>
<span class="go">False</span>
</pre></div>
</div>
<dl class="field-list simple">
<dt class="field-odd">Seealso<span class="colon">:</span></dt>
<dd class="field-odd"><p>isR, isrot2, ishom, isvec</p>
</dd>
</dl>
</dd></dl>
<dl class="py function">
<dt class="sig sig-object py" id="spatialmath.base.transforms2d.isrot2">
<span class="sig-name descname"><span class="pre">isrot2</span></span><span class="sig-paren">(</span><em class="sig-param"><span class="n"><span class="pre">R</span></span></em>, <em class="sig-param"><span class="n"><span class="pre">check</span></span><span class="o"><span class="pre">=</span></span><span class="default_value"><span class="pre">False</span></span></em>, <em class="sig-param"><span class="n"><span class="pre">tol</span></span><span class="o"><span class="pre">=</span></span><span class="default_value"><span class="pre">20</span></span></em><span class="sig-paren">)</span><a class="reference internal" href="_modules/spatialmath/base/transforms2d.html#isrot2"><span class="viewcode-link"><span class="pre">[source]</span></span></a><a class="headerlink" href="#spatialmath.base.transforms2d.isrot2" title="Permalink to this definition"></a></dt>
<dd><p>Test if matrix belongs to SO(2)</p>
<dl class="field-list simple">
<dt class="field-odd">Parameters<span class="colon">:</span></dt>
<dd class="field-odd"><ul class="simple">
<li><p><strong>R</strong> (<em>ndarray</em><em>(</em><em>3</em><em>,</em><em>3</em><em>)</em>) – SO(2) matrix to test</p></li>
<li><p><strong>check</strong> (<em>bool</em>) – check validity of rotation submatrix</p></li>
<li><p><strong>tol</strong> (<span class="sphinx_autodoc_typehints-type"><code class="xref py py-class docutils literal notranslate"><span class="pre">float</span></code></span>) – Tolerance in units of eps for zero-rotation case, defaults to 20</p></li>
</ul>
</dd>
<dt class="field-even">Type<span class="colon">:</span></dt>
<dd class="field-even"><p>float</p>
</dd>
<dt class="field-odd">Returns<span class="colon">:</span></dt>
<dd class="field-odd"><p>whether matrix is an SO(2) rotation matrix</p>
</dd>
<dt class="field-even">Return type<span class="colon">:</span></dt>
<dd class="field-even"><p>bool</p>
</dd>
</dl>
<ul class="simple">
<li><p><code class="docutils literal notranslate"><span class="pre">isrot2(R)</span></code> is True if the argument <code class="docutils literal notranslate"><span class="pre">R</span></code> is of dimension 2x2</p></li>
<li><p><code class="docutils literal notranslate"><span class="pre">isrot2(R,</span> <span class="pre">check=True)</span></code> as above, but also checks orthogonality of the rotation matrix.</p></li>
</ul>
<div class="highlight-pycon notranslate"><div class="highlight"><pre><span></span><span class="gp">>>> </span><span class="kn">from</span><span class="w"> </span><span class="nn">spatialmath.base</span><span class="w"> </span><span class="kn">import</span> <span class="o">*</span>
<span class="gp">>>> </span><span class="kn">import</span><span class="w"> </span><span class="nn">numpy</span><span class="w"> </span><span class="k">as</span><span class="w"> </span><span class="nn">np</span>
<span class="gp">>>> </span><span class="n">T</span> <span class="o">=</span> <span class="n">np</span><span class="o">.</span><span class="n">array</span><span class="p">([[</span><span class="mi">1</span><span class="p">,</span> <span class="mi">0</span><span class="p">,</span> <span class="mi">3</span><span class="p">],</span> <span class="p">[</span><span class="mi">0</span><span class="p">,</span> <span class="mi">1</span><span class="p">,</span> <span class="mi">4</span><span class="p">],</span> <span class="p">[</span><span class="mi">0</span><span class="p">,</span> <span class="mi">0</span><span class="p">,</span> <span class="mi">1</span><span class="p">]])</span>
<span class="gp">>>> </span><span class="n">isrot2</span><span class="p">(</span><span class="n">T</span><span class="p">)</span>
<span class="go">False</span>
<span class="gp">>>> </span><span class="n">R</span> <span class="o">=</span> <span class="n">np</span><span class="o">.</span><span class="n">array</span><span class="p">([[</span><span class="mi">1</span><span class="p">,</span> <span class="mi">0</span><span class="p">],</span> <span class="p">[</span><span class="mi">0</span><span class="p">,</span> <span class="mi">1</span><span class="p">]])</span>
<span class="gp">>>> </span><span class="n">isrot2</span><span class="p">(</span><span class="n">R</span><span class="p">)</span>
<span class="go">True</span>
<span class="gp">>>> </span><span class="n">R</span> <span class="o">=</span> <span class="n">np</span><span class="o">.</span><span class="n">array</span><span class="p">([[</span><span class="mi">1</span><span class="p">,</span> <span class="mi">1</span><span class="p">],</span> <span class="p">[</span><span class="mi">0</span><span class="p">,</span> <span class="mi">1</span><span class="p">]])</span> <span class="c1"># invalid SO(2)</span>
<span class="gp">>>> </span><span class="n">isrot2</span><span class="p">(</span><span class="n">R</span><span class="p">)</span> <span class="c1"># a quick check says it is an SO(2)</span>
<span class="go">True</span>
<span class="gp">>>> </span><span class="n">isrot2</span><span class="p">(</span><span class="n">R</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="c1"># but if we check more carefully...</span>
<span class="go">False</span>
</pre></div>
</div>
<dl class="field-list simple">
<dt class="field-odd">Seealso<span class="colon">:</span></dt>
<dd class="field-odd"><p>isR, ishom2, isrot</p>
</dd>
</dl>
</dd></dl>
<dl class="py function">
<dt class="sig sig-object py" id="spatialmath.base.transforms2d.points2tr2">
<span class="sig-name descname"><span class="pre">points2tr2</span></span><span class="sig-paren">(</span><em class="sig-param"><span class="n"><span class="pre">p1</span></span></em>, <em class="sig-param"><span class="n"><span class="pre">p2</span></span></em><span class="sig-paren">)</span><a class="reference internal" href="_modules/spatialmath/base/transforms2d.html#points2tr2"><span class="viewcode-link"><span class="pre">[source]</span></span></a><a class="headerlink" href="#spatialmath.base.transforms2d.points2tr2" title="Permalink to this definition"></a></dt>
<dd><p>SE(2) transform from corresponding points</p>
<dl class="field-list simple">
<dt class="field-odd">Parameters<span class="colon">:</span></dt>
<dd class="field-odd"><ul class="simple">
<li><p><strong>p1</strong> (<em>array_like</em><em>(</em><em>2</em><em>,</em><em>N</em><em>)</em>) – first set of points</p></li>
<li><p><strong>p2</strong> (<em>array_like</em><em>(</em><em>2</em><em>,</em><em>N</em><em>)</em>) – second set of points</p></li>
</ul>
</dd>
<dt class="field-even">Returns<span class="colon">:</span></dt>
<dd class="field-even"><p>transform from <code class="docutils literal notranslate"><span class="pre">p1</span></code> to <code class="docutils literal notranslate"><span class="pre">p2</span></code></p>
</dd>
<dt class="field-odd">Return type<span class="colon">:</span></dt>
<dd class="field-odd"><p>ndarray(3,3)</p>
</dd>
</dl>
<p>Compute an SE(2) matrix that transforms the point set <code class="docutils literal notranslate"><span class="pre">p1</span></code> to <code class="docutils literal notranslate"><span class="pre">p2</span></code>.
p1 and p2 must have the same number of columns, and columns correspond
to the same point.</p>
<dl class="field-list simple">
<dt class="field-odd">Seealso<span class="colon">:</span></dt>
<dd class="field-odd"><p><a class="reference internal" href="#spatialmath.base.transforms2d.ICP2d" title="spatialmath.base.transforms2d.ICP2d"><code class="xref py py-func docutils literal notranslate"><span class="pre">ICP2d()</span></code></a></p>
</dd>
</dl>
</dd></dl>
<dl class="py function">
<dt class="sig sig-object py" id="spatialmath.base.transforms2d.pos2tr2">
<span class="sig-name descname"><span class="pre">pos2tr2</span></span><span class="sig-paren">(</span><em class="sig-param"><span class="n"><span class="pre">x</span></span></em>, <em class="sig-param"><span class="n"><span class="pre">y</span></span><span class="o"><span class="pre">=</span></span><span class="default_value"><span class="pre">None</span></span></em><span class="sig-paren">)</span><a class="reference internal" href="_modules/spatialmath/base/transforms2d.html#pos2tr2"><span class="viewcode-link"><span class="pre">[source]</span></span></a><a class="headerlink" href="#spatialmath.base.transforms2d.pos2tr2" title="Permalink to this definition"></a></dt>
<dd><p>Create a translational SE(2) matrix</p>
<dl class="field-list simple">
<dt class="field-odd">Parameters<span class="colon">:</span></dt>
<dd class="field-odd"><ul class="simple">
<li><p><strong>x</strong> (<em>float</em>) – translation along X-axis</p></li>
<li><p><strong>y</strong> (<em>float</em>) – translation along Y-axis</p></li>
</ul>
</dd>
<dt class="field-even">Returns<span class="colon">:</span></dt>
<dd class="field-even"><p>SE(2) matrix</p>
</dd>
<dt class="field-odd">Return type<span class="colon">:</span></dt>
<dd class="field-odd"><p>ndarray(3,3)</p>
</dd>
</dl>
<ul class="simple">
<li><p><code class="docutils literal notranslate"><span class="pre">T</span> <span class="pre">=</span> <span class="pre">pos2tr2([X,</span> <span class="pre">Y])</span></code> is an SE(2) homogeneous transform (3x3)
representing a pure translation.</p></li>
<li><p><code class="docutils literal notranslate"><span class="pre">T</span> <span class="pre">=</span> <span class="pre">pos2tr2(</span> <span class="pre">V</span> <span class="pre">)</span></code> as above but the translation is given by a 2-element
list, dict, or a numpy array, row or column vector.</p></li>
</ul>
<div class="highlight-pycon notranslate"><div class="highlight"><pre><span></span> File <span class="nb">"<input>"</span>, line <span class="m">1</span>, in <span class="n"><module></span>
<span class="gr">NameError</span>: <span class="n">name 'pos2tr2' is not defined</span>
<span class="gt">Traceback (most recent call last):</span>
File <span class="nb">"<input>"</span>, line <span class="m">1</span>, in <span class="n"><module></span>
<span class="gr">NameError</span>: <span class="n">name 'pos2tr2' is not defined</span>
</pre></div>
</div>
<dl class="field-list simple">
<dt class="field-odd">Seealso<span class="colon">:</span></dt>
<dd class="field-odd"><p><a class="reference internal" href="#spatialmath.base.transforms2d.tr2pos2" title="spatialmath.base.transforms2d.tr2pos2"><code class="xref py py-func docutils literal notranslate"><span class="pre">tr2pos2()</span></code></a> <a class="reference internal" href="#spatialmath.base.transforms2d.transl2" title="spatialmath.base.transforms2d.transl2"><code class="xref py py-func docutils literal notranslate"><span class="pre">transl2()</span></code></a></p>
</dd>
</dl>
</dd></dl>
<dl class="py function">
<dt class="sig sig-object py" id="spatialmath.base.transforms2d.rot2">
<span class="sig-name descname"><span class="pre">rot2</span></span><span class="sig-paren">(</span><em class="sig-param"><span class="n"><span class="pre">theta</span></span></em>, <em class="sig-param"><span class="n"><span class="pre">unit</span></span><span class="o"><span class="pre">=</span></span><span class="default_value"><span class="pre">'rad'</span></span></em><span class="sig-paren">)</span><a class="reference internal" href="_modules/spatialmath/base/transforms2d.html#rot2"><span class="viewcode-link"><span class="pre">[source]</span></span></a><a class="headerlink" href="#spatialmath.base.transforms2d.rot2" title="Permalink to this definition"></a></dt>
<dd><p>Create SO(2) rotation</p>
<dl class="field-list simple">
<dt class="field-odd">Parameters<span class="colon">:</span></dt>
<dd class="field-odd"><ul class="simple">
<li><p><strong>theta</strong> (<em>float</em>) – rotation angle</p></li>
<li><p><strong>unit</strong> (<em>str</em>) – angular units: ‘rad’ [default], or ‘deg’</p></li>
</ul>
</dd>
<dt class="field-even">Returns<span class="colon">:</span></dt>
<dd class="field-even"><p>SO(2) rotation matrix</p>
</dd>
<dt class="field-odd">Return type<span class="colon">:</span></dt>
<dd class="field-odd"><p>ndarray(2,2)</p>
</dd>
</dl>
<ul class="simple">
<li><p><code class="docutils literal notranslate"><span class="pre">rot2(θ)</span></code> is an SO(2) rotation matrix (2x2) representing a rotation of θ radians.</p></li>
<li><p><code class="docutils literal notranslate"><span class="pre">rot2(θ,</span> <span class="pre">'deg')</span></code> as above but θ is in degrees.</p></li>
</ul>
<div class="highlight-pycon notranslate"><div class="highlight"><pre><span></span><span class="gp">>>> </span><span class="kn">from</span><span class="w"> </span><span class="nn">spatialmath.base</span><span class="w"> </span><span class="kn">import</span> <span class="o">*</span>
<span class="gp">>>> </span><span class="n">rot2</span><span class="p">(</span><span class="mf">0.3</span><span class="p">)</span>
<span class="go">array([[ 0.9553, -0.2955],</span>
<span class="go"> [ 0.2955, 0.9553]])</span>
<span class="gp">>>> </span><span class="n">rot2</span><span class="p">(</span><span class="mi">45</span><span class="p">,</span> <span class="s1">'deg'</span><span class="p">)</span>
<span class="go">array([[ 0.7071, -0.7071],</span>
<span class="go"> [ 0.7071, 0.7071]])</span>
</pre></div>
</div>
</dd></dl>
<dl class="py function">
<dt class="sig sig-object py" id="spatialmath.base.transforms2d.tr2jac2">
<span class="sig-name descname"><span class="pre">tr2jac2</span></span><span class="sig-paren">(</span><em class="sig-param"><span class="n"><span class="pre">T</span></span></em><span class="sig-paren">)</span><a class="reference internal" href="_modules/spatialmath/base/transforms2d.html#tr2jac2"><span class="viewcode-link"><span class="pre">[source]</span></span></a><a class="headerlink" href="#spatialmath.base.transforms2d.tr2jac2" title="Permalink to this definition"></a></dt>
<dd><p>SE(2) Jacobian matrix</p>
<dl class="field-list simple">
<dt class="field-odd">Parameters<span class="colon">:</span></dt>
<dd class="field-odd"><p><strong>T</strong> (<em>ndarray</em><em>(</em><em>3</em><em>,</em><em>3</em><em>)</em>) – SE(2) matrix</p>
</dd>
<dt class="field-even">Returns<span class="colon">:</span></dt>
<dd class="field-even"><p>Jacobian matrix</p>
</dd>
<dt class="field-odd">Return type<span class="colon">:</span></dt>
<dd class="field-odd"><p>ndarray(3,3)</p>
</dd>
</dl>
<p>Computes an Jacobian matrix that maps spatial velocity between two frames defined by
an SE(2) matrix.</p>
<p><code class="docutils literal notranslate"><span class="pre">tr2jac2(T)</span></code> is a Jacobian matrix (3x3) that maps spatial velocity or
differential motion from frame {B} to frame {A} where the pose of {B}
elative to {A} is represented by the homogeneous transform T = <span class="math notranslate nohighlight">\({}^A {\bf T}_B\)</span>.</p>
<div class="highlight-pycon notranslate"><div class="highlight"><pre><span></span><span class="gp">>>> </span><span class="kn">from</span><span class="w"> </span><span class="nn">spatialmath.base</span><span class="w"> </span><span class="kn">import</span> <span class="o">*</span>
<span class="gp">>>> </span><span class="n">T</span> <span class="o">=</span> <span class="n">trot2</span><span class="p">(</span><span class="mf">0.3</span><span class="p">,</span> <span class="n">t</span><span class="o">=</span><span class="p">[</span><span class="mi">4</span><span class="p">,</span><span class="mi">5</span><span class="p">])</span>
<span class="gp">>>> </span><span class="n">tr2jac2</span><span class="p">(</span><span class="n">T</span><span class="p">)</span>
<span class="go">array([[ 0.9553, -0.2955, 0. ],</span>
<span class="go"> [ 0.2955, 0.9553, 0. ],</span>
<span class="go"> [ 0. , 0. , 1. ]])</span>
</pre></div>
</div>
<dl class="field-list simple">
<dt class="field-odd">Reference<span class="colon">:</span></dt>
<dd class="field-odd"><p>Robotics, Vision & Control for Python, Section 3.1, P. Corke, Springer 2023.</p>
</dd>
<dt class="field-even">SymPy<span class="colon">:</span></dt>
<dd class="field-even"><p>supported</p>
</dd>
</dl>
</dd></dl>
<dl class="py function">
<dt class="sig sig-object py" id="spatialmath.base.transforms2d.tr2pos2">
<span class="sig-name descname"><span class="pre">tr2pos2</span></span><span class="sig-paren">(</span><em class="sig-param"><span class="n"><span class="pre">T</span></span></em><span class="sig-paren">)</span><a class="reference internal" href="_modules/spatialmath/base/transforms2d.html#tr2pos2"><span class="viewcode-link"><span class="pre">[source]</span></span></a><a class="headerlink" href="#spatialmath.base.transforms2d.tr2pos2" title="Permalink to this definition"></a></dt>
<dd><p>Extract translation from SE(2) matrix</p>
<dl class="field-list simple">
<dt class="field-odd">Parameters<span class="colon">:</span></dt>
<dd class="field-odd"><p><strong>x</strong> (<em>ndarray</em><em>(</em><em>3</em><em>,</em><em>3</em><em>)</em>) – SE(2) transform matrix</p>
</dd>
<dt class="field-even">Returns<span class="colon">:</span></dt>
<dd class="field-even"><p>translation elements of SE(2) matrix</p>
</dd>
<dt class="field-odd">Return type<span class="colon">:</span></dt>
<dd class="field-odd"><p>ndarray(2)</p>
</dd>
</dl>
<ul class="simple">
<li><p><code class="docutils literal notranslate"><span class="pre">t</span> <span class="pre">=</span> <span class="pre">tr2pos2(T)</span></code> is the translational part of the SE(3) matrix <code class="docutils literal notranslate"><span class="pre">T</span></code> as a
2-element NumPy array.</p></li>
</ul>
<div class="highlight-pycon notranslate"><div class="highlight"><pre><span></span>
</pre></div>
</div>
<dl class="field-list simple">
<dt class="field-odd">Seealso<span class="colon">:</span></dt>
<dd class="field-odd"><p><a class="reference internal" href="#spatialmath.base.transforms2d.pos2tr2" title="spatialmath.base.transforms2d.pos2tr2"><code class="xref py py-func docutils literal notranslate"><span class="pre">pos2tr2()</span></code></a> <a class="reference internal" href="#spatialmath.base.transforms2d.transl2" title="spatialmath.base.transforms2d.transl2"><code class="xref py py-func docutils literal notranslate"><span class="pre">transl2()</span></code></a></p>
</dd>
</dl>
</dd></dl>
<dl class="py function">
<dt class="sig sig-object py" id="spatialmath.base.transforms2d.tr2xyt">
<span class="sig-name descname"><span class="pre">tr2xyt</span></span><span class="sig-paren">(</span><em class="sig-param"><span class="n"><span class="pre">T</span></span></em>, <em class="sig-param"><span class="n"><span class="pre">unit</span></span><span class="o"><span class="pre">=</span></span><span class="default_value"><span class="pre">'rad'</span></span></em><span class="sig-paren">)</span><a class="reference internal" href="_modules/spatialmath/base/transforms2d.html#tr2xyt"><span class="viewcode-link"><span class="pre">[source]</span></span></a><a class="headerlink" href="#spatialmath.base.transforms2d.tr2xyt" title="Permalink to this definition"></a></dt>
<dd><p>Convert SE(2) to x, y, theta</p>
<dl class="field-list simple">
<dt class="field-odd">Parameters<span class="colon">:</span></dt>
<dd class="field-odd"><ul class="simple">
<li><p><strong>T</strong> (<em>ndarray</em><em>(</em><em>3</em><em>,</em><em>3</em><em>)</em>) – SE(2) matrix</p></li>
<li><p><strong>unit</strong> (<em>str</em>) – angular units: ‘rad’ [default], or ‘deg’</p></li>
</ul>
</dd>
<dt class="field-even">Returns<span class="colon">:</span></dt>
<dd class="field-even"><p>[x, y, θ]</p>
</dd>
<dt class="field-odd">Return type<span class="colon">:</span></dt>
<dd class="field-odd"><p>ndarray(3)</p>
</dd>
</dl>
<ul class="simple">
<li><p><code class="docutils literal notranslate"><span class="pre">tr2xyt(T)</span></code> is a vector giving the equivalent 2D translation and
rotation for this SO(2) matrix.</p></li>
</ul>
<div class="highlight-pycon notranslate"><div class="highlight"><pre><span></span><span class="gp">>>> </span><span class="kn">from</span><span class="w"> </span><span class="nn">spatialmath.base</span><span class="w"> </span><span class="kn">import</span> <span class="o">*</span>
<span class="gp">>>> </span><span class="n">T</span> <span class="o">=</span> <span class="n">xyt2tr</span><span class="p">([</span><span class="mi">1</span><span class="p">,</span> <span class="mi">2</span><span class="p">,</span> <span class="mf">0.3</span><span class="p">])</span>
<span class="gp">>>> </span><span class="n">T</span>
<span class="go">array([[ 0.9553, -0.2955, 1. ],</span>
<span class="go"> [ 0.2955, 0.9553, 2. ],</span>
<span class="go"> [ 0. , 0. , 1. ]])</span>
<span class="gp">>>> </span><span class="n">tr2xyt</span><span class="p">(</span><span class="n">T</span><span class="p">)</span>
<span class="go">array([1. , 2. , 0.3])</span>
</pre></div>
</div>
<dl class="field-list simple">
<dt class="field-odd">Seealso<span class="colon">:</span></dt>
<dd class="field-odd"><p>trot2</p>
</dd>
</dl>
</dd></dl>
<dl class="py function">
<dt class="sig sig-object py" id="spatialmath.base.transforms2d.tradjoint2">
<span class="sig-name descname"><span class="pre">tradjoint2</span></span><span class="sig-paren">(</span><em class="sig-param"><span class="n"><span class="pre">T</span></span></em><span class="sig-paren">)</span><a class="reference internal" href="_modules/spatialmath/base/transforms2d.html#tradjoint2"><span class="viewcode-link"><span class="pre">[source]</span></span></a><a class="headerlink" href="#spatialmath.base.transforms2d.tradjoint2" title="Permalink to this definition"></a></dt>
<dd><p>Adjoint matrix in 2D</p>
<dl class="field-list simple">
<dt class="field-odd">Parameters<span class="colon">:</span></dt>
<dd class="field-odd"><p><strong>T</strong> (<em>ndarray</em><em>(</em><em>3</em><em>,</em><em>3</em><em>) or </em><em>ndarray</em><em>(</em><em>2</em><em>,</em><em>2</em><em>)</em>) – SE(2) or SO(2) matrix</p>
</dd>
<dt class="field-even">Returns<span class="colon">:</span></dt>
<dd class="field-even"><p>adjoint matrix</p>
</dd>
<dt class="field-odd">Return type<span class="colon">:</span></dt>
<dd class="field-odd"><p>ndarray(3,3) or ndarray(1,1)</p>
</dd>
</dl>
<p>Computes an adjoint matrix that maps the Lie algebra between frames.</p>
<p>where <span class="math notranslate nohighlight">\(\mat{T} \in \SE2\)</span>.</p>
<p><code class="docutils literal notranslate"><span class="pre">tr2jac2(T)</span></code> is an adjoint matrix (6x6) that maps spatial velocity or
differential motion between frame {B} to frame {A} which are attached to the
same moving body. The pose of {B} relative to {A} is represented by the
homogeneous transform T = <span class="math notranslate nohighlight">\({}^A {\bf T}_B\)</span>.</p>
<div class="highlight-pycon notranslate"><div class="highlight"><pre><span></span> File <span class="nb">"<input>"</span>, line <span class="m">1</span>, in <span class="n"><module></span>
<span class="gr">NameError</span>: <span class="n">name 'trot2' is not defined</span>
<span class="gt">Traceback (most recent call last):</span>
File <span class="nb">"<input>"</span>, line <span class="m">1</span>, in <span class="n"><module></span>
<span class="gr">NameError</span>: <span class="n">name 'tr2adjoint2' is not defined</span>
</pre></div>
</div>
<dl class="field-list simple">
<dt class="field-odd">Reference<span class="colon">:</span></dt>
<dd class="field-odd"><ul class="simple">
<li><p>Robotics, Vision & Control for Python, Section 3.1, P. Corke, Springer 2023.</p></li>
<li><p><a href="#id1"><span class="problematic" id="id2">`</span></a>Lie groups for 2D and 3D Transformations <<a class="reference external" href="http://ethaneade.com/lie.pdf">http://ethaneade.com/lie.pdf</a>>_</p></li>
</ul>
</dd>
<dt class="field-even">SymPy<span class="colon">:</span></dt>
<dd class="field-even"><p>supported</p>
</dd>
</dl>
</dd></dl>
<dl class="py function">
<dt class="sig sig-object py" id="spatialmath.base.transforms2d.tranimate2">
<span class="sig-name descname"><span class="pre">tranimate2</span></span><span class="sig-paren">(</span><em class="sig-param"><span class="n"><span class="pre">T</span></span></em>, <em class="sig-param"><span class="o"><span class="pre">**</span></span><span class="n"><span class="pre">kwargs</span></span></em><span class="sig-paren">)</span><a class="reference internal" href="_modules/spatialmath/base/transforms2d.html#tranimate2"><span class="viewcode-link"><span class="pre">[source]</span></span></a><a class="headerlink" href="#spatialmath.base.transforms2d.tranimate2" title="Permalink to this definition"></a></dt>
<dd><p>Animate a 2D coordinate frame</p>
<dl class="field-list simple">
<dt class="field-odd">Parameters<span class="colon">:</span></dt>
<dd class="field-odd"><ul class="simple">
<li><p><strong>T</strong> (<span class="sphinx_autodoc_typehints-type"><a class="reference external" href="https://numpy.org/doc/stable/reference/generated/numpy.ndarray.html#numpy.ndarray" title="(in NumPy v2.2)"><code class="xref py py-class docutils literal notranslate"><span class="pre">ndarray</span></code></a>[<code class="xref py py-data docutils literal notranslate"><span class="pre">Any</span></code>, <a class="reference external" href="https://numpy.org/doc/stable/reference/generated/numpy.dtype.html#numpy.dtype" title="(in NumPy v2.2)"><code class="xref py py-class docutils literal notranslate"><span class="pre">dtype</span></code></a>[<code class="xref py py-class docutils literal notranslate"><span class="pre">TypeVar</span></code>(<code class="docutils literal notranslate"><span class="pre">ScalarType</span></code>, bound= <a class="reference external" href="https://numpy.org/doc/stable/reference/arrays.scalars.html#numpy.generic" title="(in NumPy v2.2)"><code class="xref py py-class docutils literal notranslate"><span class="pre">generic</span></code></a>, covariant=True)]]</span>) – an SE(2) or SO(2) pose to be displayed as coordinate frame</p></li>
<li><p><strong>nframes</strong> (<em>int</em>) – number of steps in the animation [defaault 100]</p></li>
<li><p><strong>repeat</strong> (<em>bool</em>) – animate in endless loop [default False]</p></li>
<li><p><strong>interval</strong> (<em>int</em>) – number of milliseconds between frames [default 50]</p></li>
<li><p><strong>movie</strong> (<em>str</em>) – name of file to write MP4 movie into</p></li>
</ul>
</dd>
<dt class="field-even">Type<span class="colon">:</span></dt>
<dd class="field-even"><p>ndarray(3,3) or ndarray(2,2)</p>
</dd>
</dl>
<p>Animates a 2D coordinate frame moving from the world frame to a frame represented by the SO(2) or SE(2) matrix to the current axes.</p>
<ul class="simple">
<li><p>If no current figure, one is created</p></li>
<li><p>If current figure, but no axes, a 3d Axes is created</p></li>
</ul>
<p>Examples:</p>
<blockquote>
<div><p>tranimate2(transl(1,2)@trot2(1), frame=’A’, arrow=False, dims=[0, 5])
tranimate2(transl(1,2)@trot2(1), frame=’A’, arrow=False, dims=[0, 5], movie=’spin.mp4’)</p>
</div></blockquote>
</dd></dl>
<dl class="py function">
<dt class="sig sig-object py" id="spatialmath.base.transforms2d.transl2">
<span class="sig-name descname"><span class="pre">transl2</span></span><span class="sig-paren">(</span><em class="sig-param"><span class="n"><span class="pre">x</span></span></em>, <em class="sig-param"><span class="n"><span class="pre">y</span></span><span class="o"><span class="pre">=</span></span><span class="default_value"><span class="pre">None</span></span></em><span class="sig-paren">)</span><a class="reference internal" href="_modules/spatialmath/base/transforms2d.html#transl2"><span class="viewcode-link"><span class="pre">[source]</span></span></a><a class="headerlink" href="#spatialmath.base.transforms2d.transl2" title="Permalink to this definition"></a></dt>
<dd><p>Create SE(2) pure translation, or extract translation from SE(2) matrix</p>
<p><strong>Create a translational SE(2) matrix</strong></p>
<dl class="field-list simple">
<dt class="field-odd">Parameters<span class="colon">:</span></dt>
<dd class="field-odd"><ul class="simple">
<li><p><strong>x</strong> (<em>float</em>) – translation along X-axis</p></li>
<li><p><strong>y</strong> (<em>float</em>) – translation along Y-axis</p></li>
</ul>
</dd>
<dt class="field-even">Returns<span class="colon">:</span></dt>
<dd class="field-even"><p>SE(2) matrix</p>
</dd>
<dt class="field-odd">Return type<span class="colon">:</span></dt>
<dd class="field-odd"><p>ndarray(3,3)</p>
</dd>
</dl>
<ul class="simple">
<li><p><code class="docutils literal notranslate"><span class="pre">T</span> <span class="pre">=</span> <span class="pre">transl2([X,</span> <span class="pre">Y])</span></code> is an SE(2) homogeneous transform (3x3)
representing a pure translation.</p></li>
<li><p><code class="docutils literal notranslate"><span class="pre">T</span> <span class="pre">=</span> <span class="pre">transl2(</span> <span class="pre">V</span> <span class="pre">)</span></code> as above but the translation is given by a 2-element
list, dict, or a numpy array, row or column vector.</p></li>
</ul>
<div class="highlight-pycon notranslate"><div class="highlight"><pre><span></span><span class="gp">>>> </span><span class="kn">from</span><span class="w"> </span><span class="nn">spatialmath.base</span><span class="w"> </span><span class="kn">import</span> <span class="o">*</span>
<span class="gp">>>> </span><span class="kn">import</span><span class="w"> </span><span class="nn">numpy</span><span class="w"> </span><span class="k">as</span><span class="w"> </span><span class="nn">np</span>
<span class="gp">>>> </span><span class="n">transl2</span><span class="p">(</span><span class="mi">3</span><span class="p">,</span> <span class="mi">4</span><span class="p">)</span>
<span class="go">array([[1., 0., 3.],</span>
<span class="go"> [0., 1., 4.],</span>
<span class="go"> [0., 0., 1.]])</span>
<span class="gp">>>> </span><span class="n">transl2</span><span class="p">([</span><span class="mi">3</span><span class="p">,</span> <span class="mi">4</span><span class="p">])</span>
<span class="go">array([[1., 0., 3.],</span>
<span class="go"> [0., 1., 4.],</span>
<span class="go"> [0., 0., 1.]])</span>
<span class="gp">>>> </span><span class="n">transl2</span><span class="p">(</span><span class="n">np</span><span class="o">.</span><span class="n">array</span><span class="p">([</span><span class="mi">3</span><span class="p">,</span> <span class="mi">4</span><span class="p">]))</span>
<span class="go">array([[1., 0., 3.],</span>
<span class="go"> [0., 1., 4.],</span>
<span class="go"> [0., 0., 1.]])</span>
</pre></div>
</div>
<p><strong>Extract the translational part of an SE(2) matrix</strong></p>
<dl class="field-list simple">
<dt class="field-odd">Parameters<span class="colon">:</span></dt>
<dd class="field-odd"><p><strong>x</strong> (<em>ndarray</em><em>(</em><em>3</em><em>,</em><em>3</em><em>)</em>) – SE(2) transform matrix</p>
</dd>
<dt class="field-even">Returns<span class="colon">:</span></dt>
<dd class="field-even"><p>translation elements of SE(2) matrix</p>
</dd>
<dt class="field-odd">Return type<span class="colon">:</span></dt>
<dd class="field-odd"><p>ndarray(2)</p>
</dd>
</dl>
<ul class="simple">
<li><p><code class="docutils literal notranslate"><span class="pre">t</span> <span class="pre">=</span> <span class="pre">transl2(T)</span></code> is the translational part of the SE(3) matrix <code class="docutils literal notranslate"><span class="pre">T</span></code> as a
2-element NumPy array.</p></li>
</ul>
<div class="highlight-pycon notranslate"><div class="highlight"><pre><span></span><span class="gp">>>> </span><span class="kn">from</span><span class="w"> </span><span class="nn">spatialmath.base</span><span class="w"> </span><span class="kn">import</span> <span class="o">*</span>
<span class="gp">>>> </span><span class="kn">import</span><span class="w"> </span><span class="nn">numpy</span><span class="w"> </span><span class="k">as</span><span class="w"> </span><span class="nn">np</span>
<span class="gp">>>> </span><span class="n">T</span> <span class="o">=</span> <span class="n">np</span><span class="o">.</span><span class="n">array</span><span class="p">([[</span><span class="mi">1</span><span class="p">,</span> <span class="mi">0</span><span class="p">,</span> <span class="mi">3</span><span class="p">],</span> <span class="p">[</span><span class="mi">0</span><span class="p">,</span> <span class="mi">1</span><span class="p">,</span> <span class="mi">4</span><span class="p">],</span> <span class="p">[</span><span class="mi">0</span><span class="p">,</span> <span class="mi">0</span><span class="p">,</span> <span class="mi">1</span><span class="p">]])</span>
<span class="gp">>>> </span><span class="n">transl2</span><span class="p">(</span><span class="n">T</span><span class="p">)</span>
<span class="go">array([3, 4])</span>
</pre></div>
</div>
<div class="admonition note">
<p class="admonition-title">Note</p>
<p>This function is compatible with the MATLAB version of the Toolbox. It
is unusual/weird in doing two completely different things inside the one
function.</p>
</div>
<dl class="field-list simple">
<dt class="field-odd">Seealso<span class="colon">:</span></dt>
<dd class="field-odd"><p><a class="reference internal" href="#spatialmath.base.transforms2d.tr2pos2" title="spatialmath.base.transforms2d.tr2pos2"><code class="xref py py-func docutils literal notranslate"><span class="pre">tr2pos2()</span></code></a> <a class="reference internal" href="#spatialmath.base.transforms2d.pos2tr2" title="spatialmath.base.transforms2d.pos2tr2"><code class="xref py py-func docutils literal notranslate"><span class="pre">pos2tr2()</span></code></a></p>
</dd>
</dl>
</dd></dl>
<dl class="py function">
<dt class="sig sig-object py" id="spatialmath.base.transforms2d.trexp2">
<span class="sig-name descname"><span class="pre">trexp2</span></span><span class="sig-paren">(</span><em class="sig-param"><span class="n"><span class="pre">S</span></span></em>, <em class="sig-param"><span class="n"><span class="pre">theta</span></span><span class="o"><span class="pre">=</span></span><span class="default_value"><span class="pre">None</span></span></em>, <em class="sig-param"><span class="n"><span class="pre">check</span></span><span class="o"><span class="pre">=</span></span><span class="default_value"><span class="pre">True</span></span></em><span class="sig-paren">)</span><a class="reference internal" href="_modules/spatialmath/base/transforms2d.html#trexp2"><span class="viewcode-link"><span class="pre">[source]</span></span></a><a class="headerlink" href="#spatialmath.base.transforms2d.trexp2" title="Permalink to this definition"></a></dt>
<dd><p>Exponential of so(2) or se(2) matrix</p>
<dl class="field-list simple">
<dt class="field-odd">Parameters<span class="colon">:</span></dt>
<dd class="field-odd"><ul class="simple">
<li><p><strong>S</strong> (<span class="sphinx_autodoc_typehints-type"><a class="reference external" href="https://numpy.org/doc/stable/reference/generated/numpy.ndarray.html#numpy.ndarray" title="(in NumPy v2.2)"><code class="xref py py-class docutils literal notranslate"><span class="pre">ndarray</span></code></a>[<code class="xref py py-data docutils literal notranslate"><span class="pre">Any</span></code>, <a class="reference external" href="https://numpy.org/doc/stable/reference/generated/numpy.dtype.html#numpy.dtype" title="(in NumPy v2.2)"><code class="xref py py-class docutils literal notranslate"><span class="pre">dtype</span></code></a>[<code class="xref py py-class docutils literal notranslate"><span class="pre">TypeVar</span></code>(<code class="docutils literal notranslate"><span class="pre">ScalarType</span></code>, bound= <a class="reference external" href="https://numpy.org/doc/stable/reference/arrays.scalars.html#numpy.generic" title="(in NumPy v2.2)"><code class="xref py py-class docutils literal notranslate"><span class="pre">generic</span></code></a>, covariant=True)]]</span>) – se(2), so(2) matrix or equivalent vector</p></li>
<li><p><strong>theta</strong> (<em>float</em>) – motion</p></li>
</ul>
</dd>
<dt class="field-even">Returns<span class="colon">:</span></dt>
<dd class="field-even"><p>matrix exponential in SE(2) or SO(2)</p>
</dd>
<dt class="field-odd">Return type<span class="colon">:</span></dt>
<dd class="field-odd"><p>ndarray(3,3) or ndarray(2,2)</p>
</dd>
<dt class="field-even">Raises<span class="colon">:</span></dt>
<dd class="field-even"><p><strong>ValueError</strong> – bad argument</p>
</dd>
</dl>
<p>An efficient closed-form solution of the matrix exponential for arguments
that are se(2) or so(2).</p>
<p>For se(2) the results is an SE(2) homogeneous transformation matrix:</p>
<ul class="simple">
<li><p><code class="docutils literal notranslate"><span class="pre">trexp2(Σ)</span></code> is the matrix exponential of the se(2) element <code class="docutils literal notranslate"><span class="pre">Σ</span></code> which is
a 3x3 augmented skew-symmetric matrix.</p></li>
<li><p><code class="docutils literal notranslate"><span class="pre">trexp2(Σ,</span> <span class="pre">θ)</span></code> as above but for an se(3) motion of Σθ, where <code class="docutils literal notranslate"><span class="pre">Σ</span></code>
must represent a unit-twist, ie. the rotational component is a unit-norm skew-symmetric
matrix.</p></li>
<li><p><code class="docutils literal notranslate"><span class="pre">trexp2(S)</span></code> is the matrix exponential of the se(2) element <code class="docutils literal notranslate"><span class="pre">S</span></code> represented as
a 3-vector which can be considered a screw motion.</p></li>
<li><p><code class="docutils literal notranslate"><span class="pre">trexp2(S,</span> <span class="pre">θ)</span></code> as above but for an se(2) motion of Sθ, where <code class="docutils literal notranslate"><span class="pre">S</span></code>
must represent a unit-twist, ie. the rotational component is a unit-norm skew-symmetric
matrix.</p></li>
</ul>
<div class="highlight-pycon notranslate"><div class="highlight"><pre><span></span><span class="gp">>>> </span><span class="kn">from</span><span class="w"> </span><span class="nn">spatialmath.base</span><span class="w"> </span><span class="kn">import</span> <span class="o">*</span>
<span class="gp">>>> </span><span class="n">trexp2</span><span class="p">(</span><span class="n">skew</span><span class="p">(</span><span class="mi">1</span><span class="p">))</span>
<span class="go">array([[ 0.5403, -0.8415],</span>
<span class="go"> [ 0.8415, 0.5403]])</span>
<span class="gp">>>> </span><span class="n">trexp2</span><span class="p">(</span><span class="n">skew</span><span class="p">(</span><span class="mi">1</span><span class="p">),</span> <span class="mi">2</span><span class="p">)</span> <span class="c1"># revolute unit twist</span>
<span class="go">array([[-0.4161, -0.9093],</span>
<span class="go"> [ 0.9093, -0.4161]])</span>
<span class="gp">>>> </span><span class="n">trexp2</span><span class="p">(</span><span class="mi">1</span><span class="p">)</span>
<span class="go">array([[ 0.5403, -0.8415],</span>
<span class="go"> [ 0.8415, 0.5403]])</span>
<span class="gp">>>> </span><span class="n">trexp2</span><span class="p">(</span><span class="mi">1</span><span class="p">,</span> <span class="mi">2</span><span class="p">)</span> <span class="c1"># revolute unit twist</span>
<span class="go">array([[-0.4161, -0.9093],</span>
<span class="go"> [ 0.9093, -0.4161]])</span>
</pre></div>
</div>
<p>For so(2) the results is an SO(2) rotation matrix:</p>
<ul class="simple">
<li><p><code class="docutils literal notranslate"><span class="pre">trexp2(Ω)</span></code> is the matrix exponential of the so(3) element <code class="docutils literal notranslate"><span class="pre">Ω</span></code> which is a 2x2
skew-symmetric matrix.</p></li>
<li><p><code class="docutils literal notranslate"><span class="pre">trexp2(Ω,</span> <span class="pre">θ)</span></code> as above but for an so(3) motion of Ωθ, where <code class="docutils literal notranslate"><span class="pre">Ω</span></code> is
unit-norm skew-symmetric matrix representing a rotation axis and a rotation magnitude
given by <code class="docutils literal notranslate"><span class="pre">θ</span></code>.</p></li>
<li><p><code class="docutils literal notranslate"><span class="pre">trexp2(ω)</span></code> is the matrix exponential of the so(2) element <code class="docutils literal notranslate"><span class="pre">ω</span></code> expressed as
a 1-vector.</p></li>
<li><p><code class="docutils literal notranslate"><span class="pre">trexp2(ω,</span> <span class="pre">θ)</span></code> as above but for an so(3) motion of ωθ where <code class="docutils literal notranslate"><span class="pre">ω</span></code> is a
unit-norm vector representing a rotation axis and a rotation magnitude
given by <code class="docutils literal notranslate"><span class="pre">θ</span></code>. <code class="docutils literal notranslate"><span class="pre">ω</span></code> is expressed as a 1-vector.</p></li>
</ul>
<div class="highlight-pycon notranslate"><div class="highlight"><pre><span></span><span class="gp">>>> </span><span class="kn">from</span><span class="w"> </span><span class="nn">spatialmath.base</span><span class="w"> </span><span class="kn">import</span> <span class="o">*</span>
<span class="gp">>>> </span><span class="n">trexp2</span><span class="p">(</span><span class="n">skewa</span><span class="p">([</span><span class="mi">1</span><span class="p">,</span> <span class="mi">2</span><span class="p">,</span> <span class="mi">3</span><span class="p">]))</span>
<span class="go">array([[-0.99 , -0.1411, -1.2796],</span>
<span class="go"> [ 0.1411, -0.99 , 0.7574],</span>
<span class="go"> [ 0. , 0. , 1. ]])</span>
<span class="gp">>>> </span><span class="n">trexp2</span><span class="p">(</span><span class="n">skewa</span><span class="p">([</span><span class="mi">1</span><span class="p">,</span> <span class="mi">0</span><span class="p">,</span> <span class="mi">0</span><span class="p">]),</span> <span class="mi">2</span><span class="p">)</span> <span class="c1"># prismatic unit twist</span>
<span class="go">array([[ 1., -0., 2.],</span>
<span class="go"> [ 0., 1., 0.],</span>
<span class="go"> [ 0., 0., 1.]])</span>
<span class="gp">>>> </span><span class="n">trexp2</span><span class="p">([</span><span class="mi">1</span><span class="p">,</span> <span class="mi">2</span><span class="p">,</span> <span class="mi">3</span><span class="p">])</span>
<span class="go">array([[-0.99 , -0.1411, -1.2796],</span>
<span class="go"> [ 0.1411, -0.99 , 0.7574],</span>
<span class="go"> [ 0. , 0. , 1. ]])</span>
<span class="gp">>>> </span><span class="n">trexp2</span><span class="p">([</span><span class="mi">1</span><span class="p">,</span> <span class="mi">0</span><span class="p">,</span> <span class="mi">0</span><span class="p">],</span> <span class="mi">2</span><span class="p">)</span>
<span class="go">array([[ 1., -0., 2.],</span>
<span class="go"> [ 0., 1., 0.],</span>
<span class="go"> [ 0., 0., 1.]])</span>
</pre></div>
</div>
<dl class="field-list simple">
<dt class="field-odd">Seealso<span class="colon">:</span></dt>
<dd class="field-odd"><p>trlog, trexp2</p>
</dd>
</dl>
</dd></dl>
<dl class="py function">
<dt class="sig sig-object py" id="spatialmath.base.transforms2d.trinterp2">
<span class="sig-name descname"><span class="pre">trinterp2</span></span><span class="sig-paren">(</span><em class="sig-param"><span class="n"><span class="pre">start</span></span></em>, <em class="sig-param"><span class="n"><span class="pre">end</span></span></em>, <em class="sig-param"><span class="n"><span class="pre">s</span></span></em>, <em class="sig-param"><span class="n"><span class="pre">shortest</span></span><span class="o"><span class="pre">=</span></span><span class="default_value"><span class="pre">True</span></span></em><span class="sig-paren">)</span><a class="reference internal" href="_modules/spatialmath/base/transforms2d.html#trinterp2"><span class="viewcode-link"><span class="pre">[source]</span></span></a><a class="headerlink" href="#spatialmath.base.transforms2d.trinterp2" title="Permalink to this definition"></a></dt>
<dd><p>Interpolate SE(2) or SO(2) matrices</p>
<dl class="field-list simple">
<dt class="field-odd">Parameters<span class="colon">:</span></dt>
<dd class="field-odd"><ul class="simple">
<li><p><strong>start</strong> (<em>ndarray</em><em>(</em><em>3</em><em>,</em><em>3</em><em>) or </em><em>ndarray</em><em>(</em><em>2</em><em>,</em><em>2</em><em>) or </em><em>None</em>) – initial SE(2) or SO(2) matrix value when s=0, if None then identity is used</p></li>
<li><p><strong>end</strong> (<em>ndarray</em><em>(</em><em>3</em><em>,</em><em>3</em><em>) or </em><em>ndarray</em><em>(</em><em>2</em><em>,</em><em>2</em><em>)</em>) – final SE(2) or SO(2) matrix, value when s=1</p></li>
<li><p><strong>s</strong> (<em>float</em>) – interpolation coefficient, range 0 to 1</p></li>
<li><p><strong>shortest</strong> (<em>bool</em><em>, </em><em>default to True</em>) – take the shortest path along the great circle for the rotation</p></li>
</ul>
</dd>
<dt class="field-even">Returns<span class="colon">:</span></dt>
<dd class="field-even"><p>interpolated SE(2) or SO(2) matrix value</p>
</dd>
<dt class="field-odd">Return type<span class="colon">:</span></dt>
<dd class="field-odd"><p>ndarray(3,3) or ndarray(2,2)</p>
</dd>
<dt class="field-even">Raises<span class="colon">:</span></dt>
<dd class="field-even"><p><strong>ValueError</strong> – bad arguments</p>
</dd>
</dl>
<ul class="simple">
<li><p><code class="docutils literal notranslate"><span class="pre">trinterp2(None,</span> <span class="pre">T,</span> <span class="pre">S)</span></code> is an SE(2) matrix interpolated
between identity when <cite>S`=0 and `T</cite> when <a href="#id3"><span class="problematic" id="id4">`</span></a>S`=1.</p></li>
<li><p><code class="docutils literal notranslate"><span class="pre">trinterp2(T0,</span> <span class="pre">T1,</span> <span class="pre">S)</span></code> as above but interpolated
between <cite>T0</cite> when <cite>S`=0 and `T1</cite> when <a href="#id5"><span class="problematic" id="id6">`</span></a>S`=1.</p></li>
<li><p><code class="docutils literal notranslate"><span class="pre">trinterp2(None,</span> <span class="pre">R,</span> <span class="pre">S)</span></code> is an SO(2) matrix interpolated
between identity when <cite>S`=0 and `R</cite> when <a href="#id7"><span class="problematic" id="id8">`</span></a>S`=1.</p></li>
<li><p><code class="docutils literal notranslate"><span class="pre">trinterp2(R0,</span> <span class="pre">R1,</span> <span class="pre">S)</span></code> as above but interpolated
between <cite>R0</cite> when <cite>S`=0 and `R1</cite> when <a href="#id9"><span class="problematic" id="id10">`</span></a>S`=1.</p></li>
</ul>
<div class="admonition note">
<p class="admonition-title">Note</p>
<p>Rotation angle is linearly interpolated.</p>
</div>
<div class="highlight-pycon notranslate"><div class="highlight"><pre><span></span><span class="gp">>>> </span><span class="kn">from</span><span class="w"> </span><span class="nn">spatialmath.base</span><span class="w"> </span><span class="kn">import</span> <span class="o">*</span>
<span class="gp">>>> </span><span class="n">T1</span> <span class="o">=</span> <span class="n">transl2</span><span class="p">(</span><span class="mi">1</span><span class="p">,</span> <span class="mi">2</span><span class="p">)</span>
<span class="gp">>>> </span><span class="n">T2</span> <span class="o">=</span> <span class="n">transl2</span><span class="p">(</span><span class="mi">3</span><span class="p">,</span> <span class="mi">4</span><span class="p">)</span>
<span class="gp">>>> </span><span class="n">trinterp2</span><span class="p">(</span><span class="n">T1</span><span class="p">,</span> <span class="n">T2</span><span class="p">,</span> <span class="mi">0</span><span class="p">)</span>
<span class="go">array([[ 1., -0., 1.],</span>
<span class="go"> [ 0., 1., 2.],</span>
<span class="go"> [ 0., 0., 1.]])</span>
<span class="gp">>>> </span><span class="n">trinterp2</span><span class="p">(</span><span class="n">T1</span><span class="p">,</span> <span class="n">T2</span><span class="p">,</span> <span class="mi">1</span><span class="p">)</span>
<span class="go">array([[ 1., -0., 3.],</span>
<span class="go"> [ 0., 1., 4.],</span>
<span class="go"> [ 0., 0., 1.]])</span>
<span class="gp">>>> </span><span class="n">trinterp2</span><span class="p">(</span><span class="n">T1</span><span class="p">,</span> <span class="n">T2</span><span class="p">,</span> <span class="mf">0.5</span><span class="p">)</span>
<span class="go">array([[ 1., -0., 2.],</span>
<span class="go"> [ 0., 1., 3.],</span>
<span class="go"> [ 0., 0., 1.]])</span>
<span class="gp">>>> </span><span class="n">trinterp2</span><span class="p">(</span><span class="kc">None</span><span class="p">,</span> <span class="n">T2</span><span class="p">,</span> <span class="mi">0</span><span class="p">)</span>
<span class="go">array([[ 1., -0., 0.],</span>
<span class="go"> [ 0., 1., 0.],</span>
<span class="go"> [ 0., 0., 1.]])</span>
<span class="gp">>>> </span><span class="n">trinterp2</span><span class="p">(</span><span class="kc">None</span><span class="p">,</span> <span class="n">T2</span><span class="p">,</span> <span class="mi">1</span><span class="p">)</span>
<span class="go">array([[ 1., -0., 3.],</span>
<span class="go"> [ 0., 1., 4.],</span>
<span class="go"> [ 0., 0., 1.]])</span>
<span class="gp">>>> </span><span class="n">trinterp2</span><span class="p">(</span><span class="kc">None</span><span class="p">,</span> <span class="n">T2</span><span class="p">,</span> <span class="mf">0.5</span><span class="p">)</span>
<span class="go">array([[ 1. , -0. , 1.5],</span>
<span class="go"> [ 0. , 1. , 2. ],</span>
<span class="go"> [ 0. , 0. , 1. ]])</span>
</pre></div>
</div>
<dl class="field-list simple">
<dt class="field-odd">Seealso<span class="colon">:</span></dt>
<dd class="field-odd"><p><a class="reference internal" href="func_3d.html#spatialmath.base.transforms3d.trinterp" title="spatialmath.base.transforms3d.trinterp"><code class="xref py py-func docutils literal notranslate"><span class="pre">trinterp()</span></code></a></p>
</dd>
</dl>
</dd></dl>
<dl class="py function">
<dt class="sig sig-object py" id="spatialmath.base.transforms2d.trinv2">
<span class="sig-name descname"><span class="pre">trinv2</span></span><span class="sig-paren">(</span><em class="sig-param"><span class="n"><span class="pre">T</span></span></em><span class="sig-paren">)</span><a class="reference internal" href="_modules/spatialmath/base/transforms2d.html#trinv2"><span class="viewcode-link"><span class="pre">[source]</span></span></a><a class="headerlink" href="#spatialmath.base.transforms2d.trinv2" title="Permalink to this definition"></a></dt>
<dd><p>Invert an SE(2) matrix</p>
<dl class="field-list simple">
<dt class="field-odd">Parameters<span class="colon">:</span></dt>
<dd class="field-odd"><p><strong>T</strong> (<em>ndarray</em><em>(</em><em>3</em><em>,</em><em>3</em><em>)</em>) – SE(2) matrix</p>
</dd>
<dt class="field-even">Returns<span class="colon">:</span></dt>
<dd class="field-even"><p>inverse of SE(2) matrix</p>
</dd>
<dt class="field-odd">Return type<span class="colon">:</span></dt>
<dd class="field-odd"><p>ndarray(3,3)</p>
</dd>
<dt class="field-even">Raises<span class="colon">:</span></dt>
<dd class="field-even"><p><strong>ValueError</strong> – bad arguments</p>
</dd>
</dl>
<p>Computes an efficient inverse of an SE(2) matrix:</p>
<p><span class="math notranslate nohighlight">\(\begin{pmatrix} {\bf R} & t \\ 0\,0 & 1 \end{pmatrix}^{-1} = \begin{pmatrix} {\bf R}^T & -{\bf R}^T t \\ 0\, 0 & 1 \end{pmatrix}\)</span></p>
<div class="highlight-pycon notranslate"><div class="highlight"><pre><span></span><span class="gp">>>> </span><span class="kn">from</span><span class="w"> </span><span class="nn">spatialmath.base</span><span class="w"> </span><span class="kn">import</span> <span class="o">*</span>
<span class="gp">>>> </span><span class="n">T</span> <span class="o">=</span> <span class="n">trot2</span><span class="p">(</span><span class="mf">0.3</span><span class="p">,</span> <span class="n">t</span><span class="o">=</span><span class="p">[</span><span class="mi">4</span><span class="p">,</span><span class="mi">5</span><span class="p">])</span>
<span class="gp">>>> </span><span class="n">trinv2</span><span class="p">(</span><span class="n">T</span><span class="p">)</span>
<span class="go">array([[ 0.9553, 0.2955, -5.2989],</span>
<span class="go"> [-0.2955, 0.9553, -3.5946],</span>
<span class="go"> [ 0. , 0. , 1. ]])</span>
<span class="gp">>>> </span><span class="n">T</span> <span class="o">@</span> <span class="n">trinv2</span><span class="p">(</span><span class="n">T</span><span class="p">)</span>
<span class="go">array([[ 1., -0., 0.],</span>
<span class="go"> [-0., 1., 0.],</span>
<span class="go"> [ 0., 0., 1.]])</span>
</pre></div>
</div>
<dl class="field-list simple">
<dt class="field-odd">SymPy<span class="colon">:</span></dt>
<dd class="field-odd"><p>supported</p>
</dd>
</dl>
</dd></dl>
<dl class="py function">
<dt class="sig sig-object py" id="spatialmath.base.transforms2d.trlog2">
<span class="sig-name descname"><span class="pre">trlog2</span></span><span class="sig-paren">(</span><em class="sig-param"><span class="n"><span class="pre">T</span></span></em>, <em class="sig-param"><span class="n"><span class="pre">twist</span></span><span class="o"><span class="pre">=</span></span><span class="default_value"><span class="pre">False</span></span></em>, <em class="sig-param"><span class="n"><span class="pre">check</span></span><span class="o"><span class="pre">=</span></span><span class="default_value"><span class="pre">True</span></span></em>, <em class="sig-param"><span class="n"><span class="pre">tol</span></span><span class="o"><span class="pre">=</span></span><span class="default_value"><span class="pre">20</span></span></em><span class="sig-paren">)</span><a class="reference internal" href="_modules/spatialmath/base/transforms2d.html#trlog2"><span class="viewcode-link"><span class="pre">[source]</span></span></a><a class="headerlink" href="#spatialmath.base.transforms2d.trlog2" title="Permalink to this definition"></a></dt>
<dd><p>Logarithm of SO(2) or SE(2) matrix</p>
<dl class="field-list simple">
<dt class="field-odd">Parameters<span class="colon">:</span></dt>
<dd class="field-odd"><ul class="simple">
<li><p><strong>T</strong> (<em>ndarray</em><em>(</em><em>3</em><em>,</em><em>3</em><em>) or </em><em>ndarray</em><em>(</em><em>2</em><em>,</em><em>2</em><em>)</em>) – SE(2) or SO(2) matrix</p></li>
<li><p><strong>check</strong> (<em>bool</em>) – check that matrix is valid</p></li>
<li><p><strong>twist</strong> (<em>bool</em>) – return a twist vector instead of matrix [default]</p></li>
<li><p><strong>tol</strong> (<span class="sphinx_autodoc_typehints-type"><code class="xref py py-class docutils literal notranslate"><span class="pre">float</span></code></span>) – Tolerance in units of eps for zero-rotation case, defaults to 20</p></li>
</ul>
</dd>
<dt class="field-even">Type<span class="colon">:</span></dt>
<dd class="field-even"><p>float</p>
</dd>
<dt class="field-odd">Returns<span class="colon">:</span></dt>
<dd class="field-odd"><p>logarithm</p>
</dd>
<dt class="field-even">Return type<span class="colon">:</span></dt>
<dd class="field-even"><p>ndarray(3,3) or ndarray(3); or ndarray(2,2) or ndarray(1)</p>
</dd>
<dt class="field-odd">Raises<span class="colon">:</span></dt>
<dd class="field-odd"><p><strong>ValueError</strong> – bad argument</p>
</dd>
</dl>
<p>An efficient closed-form solution of the matrix logarithm for arguments that
are SO(2) or SE(2).</p>
<ul class="simple">
<li><p><code class="docutils literal notranslate"><span class="pre">trlog2(R)</span></code> is the logarithm of the passed rotation matrix <code class="docutils literal notranslate"><span class="pre">R</span></code> which
will be 2x2 skew-symmetric matrix. The equivalent vector from <code class="docutils literal notranslate"><span class="pre">vex()</span></code>
is parallel to rotation axis and its norm is the amount of rotation about
that axis.</p></li>
<li><p><code class="docutils literal notranslate"><span class="pre">trlog(T)</span></code> is the logarithm of the passed homogeneous transformation
matrix <code class="docutils literal notranslate"><span class="pre">T</span></code> which will be 3x3 augumented skew-symmetric matrix. The
equivalent vector from <code class="docutils literal notranslate"><span class="pre">vexa()</span></code> is the twist vector (6x1) comprising [v
w].</p></li>
</ul>
<div class="highlight-pycon notranslate"><div class="highlight"><pre><span></span><span class="gp">>>> </span><span class="kn">from</span><span class="w"> </span><span class="nn">spatialmath.base</span><span class="w"> </span><span class="kn">import</span> <span class="o">*</span>
<span class="gp">>>> </span><span class="n">trlog2</span><span class="p">(</span><span class="n">trot2</span><span class="p">(</span><span class="mf">0.3</span><span class="p">))</span>
<span class="go">array([[ 0. , -0.3, 0. ],</span>
<span class="go"> [ 0.3, 0. , 0. ],</span>
<span class="go"> [ 0. , 0. , 0. ]])</span>
<span class="gp">>>> </span><span class="n">trlog2</span><span class="p">(</span><span class="n">trot2</span><span class="p">(</span><span class="mf">0.3</span><span class="p">),</span> <span class="n">twist</span><span class="o">=</span><span class="kc">True</span><span class="p">)</span>
<span class="go">array([0. , 0. , 0.3])</span>
<span class="gp">>>> </span><span class="n">trlog2</span><span class="p">(</span><span class="n">rot2</span><span class="p">(</span><span class="mf">0.3</span><span class="p">))</span>
<span class="go">array([[ 0. , -0.3],</span>
<span class="go"> [ 0.3, 0. ]])</span>
<span class="gp">>>> </span><span class="n">trlog2</span><span class="p">(</span><span class="n">rot2</span><span class="p">(</span><span class="mf">0.3</span><span class="p">),</span> <span class="n">twist</span><span class="o">=</span><span class="kc">True</span><span class="p">)</span>
<span class="go">0.3</span>
</pre></div>
</div>
<dl class="field-list simple">
<dt class="field-odd">Seealso<span class="colon">:</span></dt>
<dd class="field-odd"><p><code class="xref py py-func docutils literal notranslate"><span class="pre">trexp()</span></code>, <a class="reference internal" href="func_nd.html#spatialmath.base.transformsNd.vex" title="spatialmath.base.transformsNd.vex"><code class="xref py py-func docutils literal notranslate"><span class="pre">vex()</span></code></a>,
<a class="reference internal" href="func_nd.html#spatialmath.base.transformsNd.vexa" title="spatialmath.base.transformsNd.vexa"><code class="xref py py-func docutils literal notranslate"><span class="pre">vexa()</span></code></a></p>
</dd>
</dl>
</dd></dl>
<dl class="py function">
<dt class="sig sig-object py" id="spatialmath.base.transforms2d.trnorm2">
<span class="sig-name descname"><span class="pre">trnorm2</span></span><span class="sig-paren">(</span><em class="sig-param"><span class="n"><span class="pre">T</span></span></em><span class="sig-paren">)</span><a class="reference internal" href="_modules/spatialmath/base/transforms2d.html#trnorm2"><span class="viewcode-link"><span class="pre">[source]</span></span></a><a class="headerlink" href="#spatialmath.base.transforms2d.trnorm2" title="Permalink to this definition"></a></dt>
<dd><p>Normalize an SO(2) or SE(2) matrix</p>
<dl class="field-list simple">
<dt class="field-odd">Parameters<span class="colon">:</span></dt>
<dd class="field-odd"><p><strong>T</strong> (<em>ndarray</em><em>(</em><em>3</em><em>,</em><em>3</em><em>) or </em><em>ndarray</em><em>(</em><em>2</em><em>,</em><em>2</em><em>)</em>) – SE(2) or SO(2) matrix</p>
</dd>
<dt class="field-even">Returns<span class="colon">:</span></dt>
<dd class="field-even"><p>normalized SE(2) or SO(2) matrix</p>
</dd>
<dt class="field-odd">Return type<span class="colon">:</span></dt>
<dd class="field-odd"><p>ndarray(3,3) or ndarray(2,2)</p>
</dd>
<dt class="field-even">Raises<span class="colon">:</span></dt>
<dd class="field-even"><p><strong>ValueError</strong> – bad arguments</p>
</dd>
</dl>
<ul class="simple">
<li><p><code class="docutils literal notranslate"><span class="pre">trnorm(R)</span></code> is guaranteed to be a proper orthogonal matrix rotation
matrix (2,2) which is <em>close</em> to the input matrix R (2,2).</p></li>
<li><p><code class="docutils literal notranslate"><span class="pre">trnorm(T)</span></code> as above but the rotational submatrix of the homogeneous
transformation T (3,3) is normalised while the translational part is
unchanged.</p></li>
</ul>
<p>The steps in normalization are:</p>
<ol class="arabic simple">
<li><p>If <span class="math notranslate nohighlight">\(\mathbf{R} = [a, b]\)</span></p></li>
<li><p>Form unit vectors :math:<a href="#id11"><span class="problematic" id="id12">`</span></a>hat{b}</p></li>
<li><p>Form the orthogonal planar vector <span class="math notranslate nohighlight">\(\hat{a} = [\hat{b}_y -\hat{b}_x]\)</span></p></li>
<li><p>Form the normalized SO(2) matrix <span class="math notranslate nohighlight">\(\mathbf{R} = [\hat{a}, \hat{b}]\)</span></p></li>
</ol>
<div class="highlight-pycon notranslate"><div class="highlight"><pre><span></span> File <span class="nb">"<input>"</span>, line <span class="m">1</span>, in <span class="n"><module></span>
<span class="gr">NameError</span>: <span class="n">name 'T' is not defined</span>
<span class="gt">Traceback (most recent call last):</span>
File <span class="nb">"<input>"</span>, line <span class="m">1</span>, in <span class="n"><module></span>
<span class="gr">NameError</span>: <span class="n">name 'T' is not defined</span>
<span class="gt">Traceback (most recent call last):</span>
File <span class="nb">"<input>"</span>, line <span class="m">1</span>, in <span class="n"><module></span>
<span class="gr">NameError</span>: <span class="n">name 'T' is not defined</span>
<span class="gt">Traceback (most recent call last):</span>
File <span class="nb">"<input>"</span>, line <span class="m">1</span>, in <span class="n"><module></span>
<span class="gr">NameError</span>: <span class="n">name 'trnorm2' is not defined</span>
<span class="gt">Traceback (most recent call last):</span>
File <span class="nb">"<input>"</span>, line <span class="m">1</span>, in <span class="n"><module></span>
<span class="gr">NameError</span>: <span class="n">name 'T' is not defined</span>
</pre></div>
</div>
<div class="admonition note">
<p class="admonition-title">Note</p>
<ul class="simple">
<li><p>Only the direction of a-vector (the z-axis) is unchanged.</p></li>
<li><p>Used to prevent finite word length arithmetic causing transforms to
become ‘unnormalized’, ie. determinant <span class="math notranslate nohighlight">\(\ne 1\)</span>.</p></li>
</ul>
</div>
</dd></dl>
<dl class="py function">
<dt class="sig sig-object py" id="spatialmath.base.transforms2d.trot2">
<span class="sig-name descname"><span class="pre">trot2</span></span><span class="sig-paren">(</span><em class="sig-param"><span class="n"><span class="pre">theta</span></span></em>, <em class="sig-param"><span class="n"><span class="pre">unit</span></span><span class="o"><span class="pre">=</span></span><span class="default_value"><span class="pre">'rad'</span></span></em>, <em class="sig-param"><span class="n"><span class="pre">t</span></span><span class="o"><span class="pre">=</span></span><span class="default_value"><span class="pre">None</span></span></em><span class="sig-paren">)</span><a class="reference internal" href="_modules/spatialmath/base/transforms2d.html#trot2"><span class="viewcode-link"><span class="pre">[source]</span></span></a><a class="headerlink" href="#spatialmath.base.transforms2d.trot2" title="Permalink to this definition"></a></dt>
<dd><p>Create SE(2) pure rotation</p>
<dl class="field-list simple">
<dt class="field-odd">Parameters<span class="colon">:</span></dt>
<dd class="field-odd"><ul class="simple">
<li><p><strong>theta</strong> (<span class="sphinx_autodoc_typehints-type"><code class="xref py py-class docutils literal notranslate"><span class="pre">float</span></code></span>) – rotation angle about X-axis</p></li>
<li><p><strong>unit</strong> (<em>str</em>) – angular units: ‘rad’ [default], or ‘deg’</p></li>
<li><p><strong>t</strong> (<em>array_like</em><em>(</em><em>2</em><em>)</em>) – 2D translation vector, defaults to [0,0]</p></li>
</ul>
</dd>
<dt class="field-even">Returns<span class="colon">:</span></dt>
<dd class="field-even"><p>3x3 homogeneous transformation matrix</p>
</dd>
<dt class="field-odd">Return type<span class="colon">:</span></dt>
<dd class="field-odd"><p>ndarray(3,3)</p>
</dd>
</dl>
<ul class="simple">
<li><p><code class="docutils literal notranslate"><span class="pre">trot2(θ)</span></code> is a homogeneous transformation (3x3) representing a rotation of
θ radians.</p></li>
<li><p><code class="docutils literal notranslate"><span class="pre">trot2(θ,</span> <span class="pre">'deg')</span></code> as above but θ is in degrees.</p></li>
</ul>
<div class="highlight-pycon notranslate"><div class="highlight"><pre><span></span><span class="gp">>>> </span><span class="kn">from</span><span class="w"> </span><span class="nn">spatialmath.base</span><span class="w"> </span><span class="kn">import</span> <span class="o">*</span>
<span class="gp">>>> </span><span class="n">trot2</span><span class="p">(</span><span class="mf">0.3</span><span class="p">)</span>
<span class="go">array([[ 0.9553, -0.2955, 0. ],</span>
<span class="go"> [ 0.2955, 0.9553, 0. ],</span>
<span class="go"> [ 0. , 0. , 1. ]])</span>
<span class="gp">>>> </span><span class="n">trot2</span><span class="p">(</span><span class="mi">45</span><span class="p">,</span> <span class="s1">'deg'</span><span class="p">,</span> <span class="n">t</span><span class="o">=</span><span class="p">[</span><span class="mi">1</span><span class="p">,</span><span class="mi">2</span><span class="p">])</span>
<span class="go">array([[ 0.7071, -0.7071, 1. ],</span>
<span class="go"> [ 0.7071, 0.7071, 2. ],</span>
<span class="go"> [ 0. , 0. , 1. ]])</span>
</pre></div>
</div>
<div class="admonition note">
<p class="admonition-title">Note</p>
<p>By default, the translational component is zero but it can be
set to a non-zero value.</p>
</div>
<dl class="field-list simple">
<dt class="field-odd">Seealso<span class="colon">:</span></dt>
<dd class="field-odd"><p>xyt2tr</p>
</dd>
</dl>
</dd></dl>
<dl class="py function">
<dt class="sig sig-object py" id="spatialmath.base.transforms2d.trplot2">
<span class="sig-name descname"><span class="pre">trplot2</span></span><span class="sig-paren">(</span><em class="sig-param"><span class="n"><span class="pre">T</span></span></em>, <em class="sig-param"><span class="n"><span class="pre">color</span></span><span class="o"><span class="pre">=</span></span><span class="default_value"><span class="pre">'blue'</span></span></em>, <em class="sig-param"><span class="n"><span class="pre">frame</span></span><span class="o"><span class="pre">=</span></span><span class="default_value"><span class="pre">None</span></span></em>, <em class="sig-param"><span class="n"><span class="pre">axislabel</span></span><span class="o"><span class="pre">=</span></span><span class="default_value"><span class="pre">True</span></span></em>, <em class="sig-param"><span class="n"><span class="pre">axissubscript</span></span><span class="o"><span class="pre">=</span></span><span class="default_value"><span class="pre">True</span></span></em>, <em class="sig-param"><span class="n"><span class="pre">textcolor</span></span><span class="o"><span class="pre">=</span></span><span class="default_value"><span class="pre">None</span></span></em>, <em class="sig-param"><span class="n"><span class="pre">labels</span></span><span class="o"><span class="pre">=</span></span><span class="default_value"><span class="pre">('X',</span> <span class="pre">'Y')</span></span></em>, <em class="sig-param"><span class="n"><span class="pre">length</span></span><span class="o"><span class="pre">=</span></span><span class="default_value"><span class="pre">1</span></span></em>, <em class="sig-param"><span class="n"><span class="pre">arrow</span></span><span class="o"><span class="pre">=</span></span><span class="default_value"><span class="pre">True</span></span></em>, <em class="sig-param"><span class="n"><span class="pre">originsize</span></span><span class="o"><span class="pre">=</span></span><span class="default_value"><span class="pre">20</span></span></em>, <em class="sig-param"><span class="n"><span class="pre">rviz</span></span><span class="o"><span class="pre">=</span></span><span class="default_value"><span class="pre">False</span></span></em>, <em class="sig-param"><span class="n"><span class="pre">ax</span></span><span class="o"><span class="pre">=</span></span><span class="default_value"><span class="pre">None</span></span></em>, <em class="sig-param"><span class="n"><span class="pre">block</span></span><span class="o"><span class="pre">=</span></span><span class="default_value"><span class="pre">None</span></span></em>, <em class="sig-param"><span class="n"><span class="pre">dims</span></span><span class="o"><span class="pre">=</span></span><span class="default_value"><span class="pre">None</span></span></em>, <em class="sig-param"><span class="n"><span class="pre">wtl</span></span><span class="o"><span class="pre">=</span></span><span class="default_value"><span class="pre">0.2</span></span></em>, <em class="sig-param"><span class="n"><span class="pre">width</span></span><span class="o"><span class="pre">=</span></span><span class="default_value"><span class="pre">1</span></span></em>, <em class="sig-param"><span class="n"><span class="pre">d1</span></span><span class="o"><span class="pre">=</span></span><span class="default_value"><span class="pre">0.1</span></span></em>, <em class="sig-param"><span class="n"><span class="pre">d2</span></span><span class="o"><span class="pre">=</span></span><span class="default_value"><span class="pre">1.15</span></span></em>, <em class="sig-param"><span class="o"><span class="pre">**</span></span><span class="n"><span class="pre">kwargs</span></span></em><span class="sig-paren">)</span><a class="reference internal" href="_modules/spatialmath/base/transforms2d.html#trplot2"><span class="viewcode-link"><span class="pre">[source]</span></span></a><a class="headerlink" href="#spatialmath.base.transforms2d.trplot2" title="Permalink to this definition"></a></dt>
<dd><p>Plot a 2D coordinate frame</p>
<dl class="field-list simple">
<dt class="field-odd">Parameters<span class="colon">:</span></dt>
<dd class="field-odd"><ul class="simple">
<li><p><strong>T</strong> (<span class="sphinx_autodoc_typehints-type"><a class="reference external" href="https://numpy.org/doc/stable/reference/generated/numpy.ndarray.html#numpy.ndarray" title="(in NumPy v2.2)"><code class="xref py py-class docutils literal notranslate"><span class="pre">ndarray</span></code></a>[<code class="xref py py-data docutils literal notranslate"><span class="pre">Any</span></code>, <a class="reference external" href="https://numpy.org/doc/stable/reference/generated/numpy.dtype.html#numpy.dtype" title="(in NumPy v2.2)"><code class="xref py py-class docutils literal notranslate"><span class="pre">dtype</span></code></a>[<code class="xref py py-class docutils literal notranslate"><span class="pre">TypeVar</span></code>(<code class="docutils literal notranslate"><span class="pre">ScalarType</span></code>, bound= <a class="reference external" href="https://numpy.org/doc/stable/reference/arrays.scalars.html#numpy.generic" title="(in NumPy v2.2)"><code class="xref py py-class docutils literal notranslate"><span class="pre">generic</span></code></a>, covariant=True)]]</span>) – an SE(3) or SO(3) pose to be displayed as coordinate frame</p></li>
<li><p><strong>color</strong> (<em>str</em>) – color of the lines defining the frame</p></li>
<li><p><strong>textcolor</strong> (<em>str</em>) – color of text labels for the frame, default color of lines above</p></li>
<li><p><strong>frame</strong> (<em>str</em>) – label the frame, name is shown below the frame and as subscripts on the frame axis labels</p></li>
<li><p><strong>axislabel</strong> (<em>bool</em>) – display labels on axes, default True</p></li>
<li><p><strong>axissubscript</strong> (<em>bool</em>) – display subscripts on axis labels, default True</p></li>