-
Notifications
You must be signed in to change notification settings - Fork 91
/
Copy path3d_pose_twist.html
1554 lines (1486 loc) · 120 KB
/
3d_pose_twist.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>se(3) twist — 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="Unit dual quaternion" href="3d_pose_dualquaternion.html" />
<link rel="prev" title="SE(3) matrix" href="3d_pose_SE3.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 current"><a class="reference internal" href="spatialmath.html">Class reference</a><ul class="current">
<li class="toctree-l2 current"><a class="reference internal" href="spatialmath.html#d-space">3D-space</a><ul class="current">
<li class="toctree-l3 current"><a class="reference internal" href="spatialmath.html#pose-in-3d">Pose in 3D</a><ul class="current">
<li class="toctree-l4"><a class="reference internal" href="3d_pose_SE3.html">SE(3) matrix</a></li>
<li class="toctree-l4 current"><a class="current reference internal" href="#">se(3) twist</a></li>
<li class="toctree-l4"><a class="reference internal" href="3d_pose_dualquaternion.html">Unit dual quaternion</a></li>
</ul>
</li>
<li class="toctree-l3"><a class="reference internal" href="spatialmath.html#orientation-in-3d">Orientation in 3D</a></li>
<li class="toctree-l3"><a class="reference internal" href="spatialmath.html#d-spatial-vectors">6D spatial vectors</a></li>
<li class="toctree-l3"><a class="reference internal" href="spatialmath.html#geometry-in-3d">Geometry in 3D</a></li>
<li class="toctree-l3"><a class="reference internal" href="spatialmath.html#supporting">Supporting</a></li>
</ul>
</li>
<li class="toctree-l2"><a class="reference internal" href="spatialmath.html#id1">2D-space</a></li>
</ul>
</li>
<li class="toctree-l1"><a class="reference internal" href="functions.html">Function reference</a></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="spatialmath.html">Class reference</a></li>
<li class="breadcrumb-item active">se(3) twist</li>
<li class="wy-breadcrumbs-aside">
<a href="_sources/3d_pose_twist.rst.txt" rel="nofollow"> View page source</a>
</li>
</ul><div class="rst-breadcrumbs-buttons" role="navigation" aria-label="Sequential page navigation">
<a href="3d_pose_SE3.html" class="btn btn-neutral float-left" title="SE(3) matrix" accesskey="p"><span class="fa fa-arrow-circle-left" aria-hidden="true"></span> Previous</a>
<a href="3d_pose_dualquaternion.html" class="btn btn-neutral float-right" title="Unit dual quaternion" 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="se-3-twist">
<h1>se(3) twist<a class="headerlink" href="#se-3-twist" title="Permalink to this heading"></a></h1>
<dl class="py class">
<dt class="sig sig-object py" id="spatialmath.twist.Twist3">
<em class="property"><span class="pre">class</span><span class="w"> </span></em><span class="sig-name descname"><span class="pre">Twist3</span></span><span class="sig-paren">(</span><em class="sig-param"><span class="n"><span class="pre">arg</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">w</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/twist.html#Twist3"><span class="viewcode-link"><span class="pre">[source]</span></span></a><a class="headerlink" href="#spatialmath.twist.Twist3" title="Permalink to this definition"></a></dt>
<dd><p>Bases: <code class="xref py py-class docutils literal notranslate"><span class="pre">BaseTwist</span></code></p>
<p>3D twist class</p>
<p>A Twist class holds the parameters of a twist, a representation of a
3D rigid body transformation which is the unique elements of the Lie
algebra se(3) of the corresponding SE(3) matrix.</p>
<dl class="field-list simple">
<dt class="field-odd">References<span class="colon">:</span></dt>
<dd class="field-odd"><ul class="simple">
<li><p>Robotics, Vision & Control for Python, Section 2.3.2.3, P. Corke, Springer 2023.</p></li>
<li><p>Modern Robotics, Lynch & Park, Cambridge 2017</p></li>
</ul>
</dd>
</dl>
<div class="admonition note">
<p class="admonition-title">Note</p>
<p>Compared to Lynch & Park this module implements twist vectors
with the translational components first, followed by rotational
components, ie. <span class="math notranslate nohighlight">\([\omega, \vec{v}]\)</span>.</p>
</div>
<dl class="py method">
<dt class="sig sig-object py" id="spatialmath.twist.Twist3.Ad">
<span class="sig-name descname"><span class="pre">Ad</span></span><span class="sig-paren">(</span><span class="sig-paren">)</span><a class="reference internal" href="_modules/spatialmath/twist.html#Twist3.Ad"><span class="viewcode-link"><span class="pre">[source]</span></span></a><a class="headerlink" href="#spatialmath.twist.Twist3.Ad" title="Permalink to this definition"></a></dt>
<dd><p>Adjoint of 3D twist</p>
<dl class="field-list simple">
<dt class="field-odd">Returns<span class="colon">:</span></dt>
<dd class="field-odd"><p>adjoint matrix</p>
</dd>
<dt class="field-even">Return type<span class="colon">:</span></dt>
<dd class="field-even"><p>ndarray(6,6)</p>
</dd>
</dl>
<p><code class="docutils literal notranslate"><span class="pre">S.Ad()</span></code> is the 6x6 adjoint matrix of the corresponding
homogeneous transformation.</p>
<p>For a twist representing motion from frame {B} to {A}, the adjoint will
transform a twist relative to frame {A} to one relative to frame {B}.</p>
<p>Example:</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</span><span class="w"> </span><span class="kn">import</span> <span class="n">Twist3</span>
<span class="gp">>>> </span><span class="n">S</span> <span class="o">=</span> <span class="n">Twist3</span><span class="o">.</span><span class="n">Rx</span><span class="p">(</span><span class="mf">0.3</span><span class="p">)</span>
<span class="gp">>>> </span><span class="n">S</span><span class="o">.</span><span class="n">Ad</span><span class="p">()</span>
<span class="go">array([[ 1. , 0. , 0. , 0. , 0. , 0. ],</span>
<span class="go"> [ 0. , 0.9553, -0.2955, 0. , 0. , 0. ],</span>
<span class="go"> [ 0. , 0.2955, 0.9553, 0. , 0. , 0. ],</span>
<span class="go"> [ 0. , 0. , 0. , 1. , 0. , 0. ],</span>
<span class="go"> [ 0. , 0. , 0. , 0. , 0.9553, -0.2955],</span>
<span class="go"> [ 0. , 0. , 0. , 0. , 0.2955, 0.9553]])</span>
</pre></div>
</div>
<div class="admonition note">
<p class="admonition-title">Note</p>
<p>This method computes the equivalent SE(3) matrix, then the adjoint
of that.</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.twist.Twist3.ad" title="spatialmath.twist.Twist3.ad"><code class="xref py py-func docutils literal notranslate"><span class="pre">Twist3.ad()</span></code></a>, <a class="reference internal" href="#spatialmath.twist.Twist3.SE3" title="spatialmath.twist.Twist3.SE3"><code class="xref py py-func docutils literal notranslate"><span class="pre">Twist3.SE3()</span></code></a>, <a class="reference internal" href="#spatialmath.twist.Twist3.exp" title="spatialmath.twist.Twist3.exp"><code class="xref py py-func docutils literal notranslate"><span class="pre">Twist3.exp()</span></code></a></p>
</dd>
</dl>
</dd></dl>
<dl class="py method">
<dt class="sig sig-object py" id="spatialmath.twist.Twist3.Alloc">
<em class="property"><span class="pre">classmethod</span><span class="w"> </span></em><span class="sig-name descname"><span class="pre">Alloc</span></span><span class="sig-paren">(</span><em class="sig-param"><span class="n"><span class="pre">n</span></span><span class="o"><span class="pre">=</span></span><span class="default_value"><span class="pre">1</span></span></em><span class="sig-paren">)</span><a class="headerlink" href="#spatialmath.twist.Twist3.Alloc" title="Permalink to this definition"></a></dt>
<dd><p>Construct an instance with N default values (BasePoseList superclass method)</p>
<dl class="field-list simple">
<dt class="field-odd">Parameters<span class="colon">:</span></dt>
<dd class="field-odd"><p><strong>n</strong> (<em>int</em><em>, </em><em>optional</em>) – Number of values, defaults to 1</p>
</dd>
<dt class="field-even">Return type<span class="colon">:</span></dt>
<dd class="field-even"><p><span class="sphinx_autodoc_typehints-type"><code class="xref py py-class docutils literal notranslate"><span class="pre">Self</span></code></span></p>
</dd>
<dt class="field-odd">Returns<span class="colon">:</span></dt>
<dd class="field-odd"><p>pose instance with <code class="docutils literal notranslate"><span class="pre">n</span></code> default values</p>
</dd>
</dl>
<p><code class="docutils literal notranslate"><span class="pre">X.Alloc(N)</span></code> creates an instance of the pose class <code class="docutils literal notranslate"><span class="pre">X</span></code> with <code class="docutils literal notranslate"><span class="pre">N</span></code>
default values, ie. <code class="docutils literal notranslate"><span class="pre">len(X)</span></code> will be <code class="docutils literal notranslate"><span class="pre">N</span></code>.</p>
<p><code class="docutils literal notranslate"><span class="pre">X</span></code> can be considered a vector of pose objects, and those elements
can be referenced <code class="docutils literal notranslate"><span class="pre">X[i]</span></code> or assigned to <code class="docutils literal notranslate"><span class="pre">X[i]</span> <span class="pre">=</span> <span class="pre">...</span></code>.</p>
<div class="admonition note">
<p class="admonition-title">Note</p>
<p>The default value depends on the pose class and is the result
of the empty constructor. For <code class="docutils literal notranslate"><span class="pre">SO2</span></code>,
<code class="docutils literal notranslate"><span class="pre">SE2</span></code>, <code class="docutils literal notranslate"><span class="pre">SO3</span></code>, <code class="docutils literal notranslate"><span class="pre">SE3</span></code> it is an identity matrix, for a
twist class <code class="docutils literal notranslate"><span class="pre">Twist2</span></code> or <code class="docutils literal notranslate"><span class="pre">Twist3</span></code> it is a zero vector,
for a <code class="docutils literal notranslate"><span class="pre">UnitQuaternion</span></code> or <code class="docutils literal notranslate"><span class="pre">Quaternion</span></code> it is a zero
vector.</p>
</div>
<p>Example:</p>
<div class="highlight-default notranslate"><div class="highlight"><pre><span></span><span class="gp">>>> </span><span class="n">x</span> <span class="o">=</span> <span class="n">X</span><span class="o">.</span><span class="n">Alloc</span><span class="p">(</span><span class="mi">10</span><span class="p">)</span>
<span class="gp">>>> </span><span class="nb">len</span><span class="p">(</span><span class="n">x</span><span class="p">)</span>
<span class="go">10</span>
</pre></div>
</div>
<p>where <code class="docutils literal notranslate"><span class="pre">X</span></code> is any of the SMTB classes.</p>
</dd></dl>
<dl class="py method">
<dt class="sig sig-object py" id="spatialmath.twist.Twist3.Empty">
<em class="property"><span class="pre">classmethod</span><span class="w"> </span></em><span class="sig-name descname"><span class="pre">Empty</span></span><span class="sig-paren">(</span><span class="sig-paren">)</span><a class="headerlink" href="#spatialmath.twist.Twist3.Empty" title="Permalink to this definition"></a></dt>
<dd><p>Construct an empty instance (BasePoseList superclass method)</p>
<dl class="field-list simple">
<dt class="field-odd">Return type<span class="colon">:</span></dt>
<dd class="field-odd"><p><span class="sphinx_autodoc_typehints-type"><code class="xref py py-class docutils literal notranslate"><span class="pre">Self</span></code></span></p>
</dd>
<dt class="field-even">Returns<span class="colon">:</span></dt>
<dd class="field-even"><p>pose instance with zero values</p>
</dd>
</dl>
<p>Example:</p>
<div class="highlight-default notranslate"><div class="highlight"><pre><span></span><span class="gp">>>> </span><span class="n">x</span> <span class="o">=</span> <span class="n">X</span><span class="o">.</span><span class="n">Empty</span><span class="p">()</span>
<span class="gp">>>> </span><span class="nb">len</span><span class="p">(</span><span class="n">x</span><span class="p">)</span>
<span class="go">0</span>
</pre></div>
</div>
<p>where <code class="docutils literal notranslate"><span class="pre">X</span></code> is any of the SMTB classes.</p>
</dd></dl>
<dl class="py method">
<dt class="sig sig-object py" id="spatialmath.twist.Twist3.RPY">
<em class="property"><span class="pre">classmethod</span><span class="w"> </span></em><span class="sig-name descname"><span class="pre">RPY</span></span><span class="sig-paren">(</span><em class="sig-param"><span class="o"><span class="pre">*</span></span><span class="n"><span class="pre">pos</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/twist.html#Twist3.RPY"><span class="viewcode-link"><span class="pre">[source]</span></span></a><a class="headerlink" href="#spatialmath.twist.Twist3.RPY" title="Permalink to this definition"></a></dt>
<dd><p>Create a new 3D twist from roll-pitch-yaw angles</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>𝚪</strong> (<em>array_like</em><em> or </em><em>numpy.ndarray with shape=</em><em>(</em><em>N</em><em>,</em><em>3</em><em>)</em>) – roll-pitch-yaw angles</p></li>
<li><p><strong>unit</strong> (<em>str</em>) – angular units: ‘rad’ [default], or ‘deg’</p></li>
<li><p><strong>order</strong> (<em>str</em>) – rotation order: ‘zyx’ [default], ‘xyz’, or ‘yxz’</p></li>
</ul>
</dd>
<dt class="field-even">Returns<span class="colon">:</span></dt>
<dd class="field-even"><p>3D twist vector</p>
</dd>
<dt class="field-odd">Return type<span class="colon">:</span></dt>
<dd class="field-odd"><p>Twist3 instance</p>
</dd>
</dl>
<ul>
<li><p><code class="docutils literal notranslate"><span class="pre">Twist3.RPY(𝚪)</span></code> is a 3D rotation defined by a 3-vector of roll,
pitch, yaw angles <span class="math notranslate nohighlight">\(\Gamma=(r, p, y)\)</span> which correspond to
successive rotations about the axes specified by <code class="docutils literal notranslate"><span class="pre">order</span></code>:</p>
<blockquote>
<div><ul class="simple">
<li><p><code class="docutils literal notranslate"><span class="pre">'zyx'</span></code> [default], rotate by yaw about the z-axis, then by pitch about the new y-axis,
then by roll about the new x-axis. This is the <strong>convention</strong> for a mobile robot with x-axis forward
and y-axis sideways.</p></li>
<li><p><code class="docutils literal notranslate"><span class="pre">'xyz'</span></code>, rotate by yaw about the x-axis, then by pitch about the new y-axis,
then by roll about the new z-axis. This is the <strong>convention</strong> for a robot gripper with z-axis forward
and y-axis between the gripper fingers.</p></li>
<li><p><code class="docutils literal notranslate"><span class="pre">'yxz'</span></code>, rotate by yaw about the y-axis, then by pitch about the new x-axis,
then by roll about the new z-axis. This is the <strong>convention</strong> for a camera with z-axis parallel
to the optical axis and x-axis parallel to the pixel rows.</p></li>
</ul>
</div></blockquote>
</li>
</ul>
<p>If <code class="docutils literal notranslate"><span class="pre">𝚪</span></code> is an Nx3 matrix then the result is a sequence of rotations each defined by RPY angles
corresponding to the rows of <code class="docutils literal notranslate"><span class="pre">𝚪</span></code>.</p>
<ul class="simple">
<li><p><code class="docutils literal notranslate"><span class="pre">Twist3.RPY(⍺,</span> <span class="pre">β,</span> <span class="pre">𝛾)</span></code> as above but the angles are provided as three
scalars.</p></li>
</ul>
<p>Foo bar!</p>
<p>Example:</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</span><span class="w"> </span><span class="kn">import</span> <span class="n">Twist3</span>
<span class="gp">>>> </span><span class="n">Twist3</span><span class="o">.</span><span class="n">RPY</span><span class="p">(</span><span class="mf">0.1</span><span class="p">,</span> <span class="mf">0.2</span><span class="p">,</span> <span class="mf">0.3</span><span class="p">)</span>
<span class="go">Twist3([0, 0, 0, 0.068925, 0.21323, 0.28875])</span>
<span class="gp">>>> </span><span class="n">Twist3</span><span class="o">.</span><span class="n">RPY</span><span class="p">([</span><span class="mf">0.1</span><span class="p">,</span> <span class="mf">0.2</span><span class="p">,</span> <span class="mf">0.3</span><span class="p">])</span>
<span class="go">Twist3([0, 0, 0, 0.068925, 0.21323, 0.28875])</span>
<span class="gp">>>> </span><span class="n">Twist3</span><span class="o">.</span><span class="n">RPY</span><span class="p">(</span><span class="mf">0.1</span><span class="p">,</span> <span class="mf">0.2</span><span class="p">,</span> <span class="mf">0.3</span><span class="p">,</span> <span class="n">order</span><span class="o">=</span><span class="s1">'xyz'</span><span class="p">)</span>
<span class="go">Twist3([0, 0, 0, 0.30875, 0.18343, 0.12892])</span>
<span class="gp">>>> </span><span class="n">Twist3</span><span class="o">.</span><span class="n">RPY</span><span class="p">(</span><span class="mi">10</span><span class="p">,</span> <span class="mi">20</span><span class="p">,</span> <span class="mi">30</span><span class="p">,</span> <span class="n">unit</span><span class="o">=</span><span class="s1">'deg'</span><span class="p">)</span>
<span class="go">Twist3([0, 0, 0, 0.077525, 0.38485, 0.48648])</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-meth docutils literal notranslate"><span class="pre">RPY()</span></code></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 method">
<dt class="sig sig-object py" id="spatialmath.twist.Twist3.Rand">
<em class="property"><span class="pre">classmethod</span><span class="w"> </span></em><span class="sig-name descname"><span class="pre">Rand</span></span><span class="sig-paren">(</span><em class="sig-param"><span class="o"><span class="pre">*</span></span></em>, <em class="sig-param"><span class="n"><span class="pre">xrange</span></span><span class="o"><span class="pre">=</span></span><span class="default_value"><span class="pre">(-1,</span> <span class="pre">1)</span></span></em>, <em class="sig-param"><span class="n"><span class="pre">yrange</span></span><span class="o"><span class="pre">=</span></span><span class="default_value"><span class="pre">(-1,</span> <span class="pre">1)</span></span></em>, <em class="sig-param"><span class="n"><span class="pre">zrange</span></span><span class="o"><span class="pre">=</span></span><span class="default_value"><span class="pre">(-1,</span> <span class="pre">1)</span></span></em>, <em class="sig-param"><span class="n"><span class="pre">N</span></span><span class="o"><span class="pre">=</span></span><span class="default_value"><span class="pre">1</span></span></em><span class="sig-paren">)</span><a class="reference internal" href="_modules/spatialmath/twist.html#Twist3.Rand"><span class="viewcode-link"><span class="pre">[source]</span></span></a><a class="headerlink" href="#spatialmath.twist.Twist3.Rand" title="Permalink to this definition"></a></dt>
<dd><p>Create a new random 3D twist</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>xrange</strong> (<em>2-element sequence</em><em>, </em><em>optional</em>) – x-axis range [min,max], defaults to [-1, 1]</p></li>
<li><p><strong>yrange</strong> (<em>2-element sequence</em><em>, </em><em>optional</em>) – y-axis range [min,max], defaults to [-1, 1]</p></li>
<li><p><strong>zrange</strong> (<em>2-element sequence</em><em>, </em><em>optional</em>) – z-axis range [min,max], defaults to [-1, 1]</p></li>
<li><p><strong>N</strong> (<em>int</em>) – number of random transforms</p></li>
</ul>
</dd>
<dt class="field-even">Returns<span class="colon">:</span></dt>
<dd class="field-even"><p>SE(3) matrix</p>
</dd>
<dt class="field-odd">Return type<span class="colon">:</span></dt>
<dd class="field-odd"><p>SE3 instance</p>
</dd>
</dl>
<p>Return an SE3 instance with random rotation and translation.</p>
<ul class="simple">
<li><p><code class="docutils literal notranslate"><span class="pre">SE3.Rand()</span></code> is a random SE(3) translation.</p></li>
<li><p><code class="docutils literal notranslate"><span class="pre">SE3.Rand(N=N)</span></code> is an SE3 object containing a sequence of N random
poses.</p></li>
</ul>
<p>Example:</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</span><span class="w"> </span><span class="kn">import</span> <span class="n">Twist3</span>
<span class="gp">>>> </span><span class="n">Twist3</span><span class="o">.</span><span class="n">Rand</span><span class="p">(</span><span class="n">N</span><span class="o">=</span><span class="mi">2</span><span class="p">)</span>
<span class="go">Twist3([</span>
<span class="go"> [0.70508, -0.42951, -0.75073, -1.2984, 1.9579, -1.9477],</span>
<span class="go"> [0.95669, 0.20993, 0.56213, 0.14053, -1.0451, -0.21306]</span>
<span class="go">])</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">Rand()</span></code></p>
</dd>
</dl>
</dd></dl>
<dl class="py method">
<dt class="sig sig-object py" id="spatialmath.twist.Twist3.Rx">
<em class="property"><span class="pre">classmethod</span><span class="w"> </span></em><span class="sig-name descname"><span class="pre">Rx</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/twist.html#Twist3.Rx"><span class="viewcode-link"><span class="pre">[source]</span></span></a><a class="headerlink" href="#spatialmath.twist.Twist3.Rx" title="Permalink to this definition"></a></dt>
<dd><p>Create a new 3D twist for pure rotation about the X-axis</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>θ</strong> (<em>float</em>) – rotation angle about X-axis</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>3D twist vector</p>
</dd>
<dt class="field-odd">Return type<span class="colon">:</span></dt>
<dd class="field-odd"><p>Twist3 instance</p>
</dd>
</dl>
<ul class="simple">
<li><p><code class="docutils literal notranslate"><span class="pre">Twist3.Rx(θ)</span></code> is an SE(3) rotation of θ radians about the x-axis</p></li>
<li><p><code class="docutils literal notranslate"><span class="pre">Twist3.Rx(θ,</span> <span class="pre">"deg")</span></code> as above but θ is in degrees</p></li>
</ul>
<p>If <code class="docutils literal notranslate"><span class="pre">θ</span></code> is an array then the result is a sequence of rotations defined
by consecutive elements.</p>
<p>Example:</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</span><span class="w"> </span><span class="kn">import</span> <span class="n">Twist3</span>
<span class="gp">>>> </span><span class="n">Twist3</span><span class="o">.</span><span class="n">Rx</span><span class="p">(</span><span class="mf">0.3</span><span class="p">)</span>
<span class="go">Twist3([0, 0, 0, 0.3, 0, 0])</span>
<span class="gp">>>> </span><span class="n">Twist3</span><span class="o">.</span><span class="n">Rx</span><span class="p">([</span><span class="mf">0.3</span><span class="p">,</span> <span class="mf">0.4</span><span class="p">])</span>
<span class="go">Twist3([</span>
<span class="go"> [0, 0, 0, 0.3, 0, 0],</span>
<span class="go"> [0, 0, 0, 0.4, 0, 0]</span>
<span class="go">])</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">trotx()</span></code></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 method">
<dt class="sig sig-object py" id="spatialmath.twist.Twist3.Ry">
<em class="property"><span class="pre">classmethod</span><span class="w"> </span></em><span class="sig-name descname"><span class="pre">Ry</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/twist.html#Twist3.Ry"><span class="viewcode-link"><span class="pre">[source]</span></span></a><a class="headerlink" href="#spatialmath.twist.Twist3.Ry" title="Permalink to this definition"></a></dt>
<dd><p>Create a new 3D twist for pure rotation about the Y-axis</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>θ</strong> (<em>float</em>) – rotation angle about X-axis</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>3D twist vector</p>
</dd>
<dt class="field-odd">Return type<span class="colon">:</span></dt>
<dd class="field-odd"><p>Twist3 instance</p>
</dd>
</dl>
<ul class="simple">
<li><p><code class="docutils literal notranslate"><span class="pre">Twist3.Ry(θ)</span></code> is an SO(3) rotation of θ radians about the y-axis</p></li>
<li><p><code class="docutils literal notranslate"><span class="pre">Twist3.Ry(θ,</span> <span class="pre">"deg")</span></code> as above but θ is in degrees</p></li>
</ul>
<p>If <code class="docutils literal notranslate"><span class="pre">θ</span></code> is an array then the result is a sequence of rotations defined
by consecutive elements.</p>
<p>Example:</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</span><span class="w"> </span><span class="kn">import</span> <span class="n">Twist3</span>
<span class="gp">>>> </span><span class="n">Twist3</span><span class="o">.</span><span class="n">Ry</span><span class="p">(</span><span class="mf">0.3</span><span class="p">)</span>
<span class="go">Twist3([0, 0, 0, 0, 0.3, 0])</span>
<span class="gp">>>> </span><span class="n">Twist3</span><span class="o">.</span><span class="n">Ry</span><span class="p">([</span><span class="mf">0.3</span><span class="p">,</span> <span class="mf">0.4</span><span class="p">])</span>
<span class="go">Twist3([</span>
<span class="go"> [0, 0, 0, 0, 0.3, 0],</span>
<span class="go"> [0, 0, 0, 0, 0.4, 0]</span>
<span class="go">])</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">troty()</span></code></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 method">
<dt class="sig sig-object py" id="spatialmath.twist.Twist3.Rz">
<em class="property"><span class="pre">classmethod</span><span class="w"> </span></em><span class="sig-name descname"><span class="pre">Rz</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/twist.html#Twist3.Rz"><span class="viewcode-link"><span class="pre">[source]</span></span></a><a class="headerlink" href="#spatialmath.twist.Twist3.Rz" title="Permalink to this definition"></a></dt>
<dd><p>Create a new 3D twist for pure rotation about the Z-axis</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>θ</strong> (<em>float</em>) – rotation angle about Z-axis</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>3D twist vector</p>
</dd>
<dt class="field-odd">Return type<span class="colon">:</span></dt>
<dd class="field-odd"><p>Twist3 instance</p>
</dd>
</dl>
<ul class="simple">
<li><p><code class="docutils literal notranslate"><span class="pre">Twist3.Rz(θ)</span></code> is an SO(3) rotation of θ radians about the z-axis</p></li>
<li><p><code class="docutils literal notranslate"><span class="pre">Twist3.Rz(θ,</span> <span class="pre">"deg")</span></code> as above but θ is in degrees</p></li>
</ul>
<p>If <code class="docutils literal notranslate"><span class="pre">θ</span></code> is an array then the result is a sequence of rotations defined
by consecutive elements.</p>
<p>Example:</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</span><span class="w"> </span><span class="kn">import</span> <span class="n">Twist3</span>
<span class="gp">>>> </span><span class="n">Twist3</span><span class="o">.</span><span class="n">Rz</span><span class="p">(</span><span class="mf">0.3</span><span class="p">)</span>
<span class="go">Twist3([0, 0, 0, 0, 0, 0.3])</span>
<span class="gp">>>> </span><span class="n">Twist3</span><span class="o">.</span><span class="n">Rz</span><span class="p">([</span><span class="mf">0.3</span><span class="p">,</span> <span class="mf">0.4</span><span class="p">])</span>
<span class="go">Twist3([</span>
<span class="go"> [0, 0, 0, 0, 0, 0.3],</span>
<span class="go"> [0, 0, 0, 0, 0, 0.4]</span>
<span class="go">])</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">trotz()</span></code></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 method">
<dt class="sig sig-object py" id="spatialmath.twist.Twist3.SE3">
<span class="sig-name descname"><span class="pre">SE3</span></span><span class="sig-paren">(</span><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">1</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/twist.html#Twist3.SE3"><span class="viewcode-link"><span class="pre">[source]</span></span></a><a class="headerlink" href="#spatialmath.twist.Twist3.SE3" title="Permalink to this definition"></a></dt>
<dd><p>Convert 3D twist to SE(3) matrix</p>
<dl class="field-list simple">
<dt class="field-odd">Returns<span class="colon">:</span></dt>
<dd class="field-odd"><p>an SE(3) representation</p>
</dd>
<dt class="field-even">Return type<span class="colon">:</span></dt>
<dd class="field-even"><p>SE3 instance</p>
</dd>
</dl>
<p><code class="docutils literal notranslate"><span class="pre">S.SE3()</span></code> is an SE3 object representing the homogeneous transformation
equivalent to the Twist3. This is the exponentiation of the twist vector.</p>
<p>Example:</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</span><span class="w"> </span><span class="kn">import</span> <span class="n">Twist3</span>
<span class="gp">>>> </span><span class="n">S</span> <span class="o">=</span> <span class="n">Twist3</span><span class="o">.</span><span class="n">Rx</span><span class="p">(</span><span class="mf">0.3</span><span class="p">)</span>
<span class="gp">>>> </span><span class="n">S</span><span class="o">.</span><span class="n">SE3</span><span class="p">()</span>
<span class="go">SE3(array([[ 1. , 0. , 0. , 0. ],</span>
<span class="go"> [ 0. , 0.9553, -0.2955, 0. ],</span>
<span class="go"> [ 0. , 0.2955, 0.9553, 0. ],</span>
<span class="go"> [ 0. , 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="#spatialmath.twist.Twist3.exp" title="spatialmath.twist.Twist3.exp"><code class="xref py py-func docutils literal notranslate"><span class="pre">Twist3.exp()</span></code></a></p>
</dd>
</dl>
</dd></dl>
<dl class="py method">
<dt class="sig sig-object py" id="spatialmath.twist.Twist3.Tx">
<em class="property"><span class="pre">classmethod</span><span class="w"> </span></em><span class="sig-name descname"><span class="pre">Tx</span></span><span class="sig-paren">(</span><em class="sig-param"><span class="n"><span class="pre">x</span></span></em><span class="sig-paren">)</span><a class="reference internal" href="_modules/spatialmath/twist.html#Twist3.Tx"><span class="viewcode-link"><span class="pre">[source]</span></span></a><a class="headerlink" href="#spatialmath.twist.Twist3.Tx" title="Permalink to this definition"></a></dt>
<dd><p>Create a new 3D twist for pure translation along the X-axis</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>float</em>) – translation distance along the X-axis</p>
</dd>
<dt class="field-even">Returns<span class="colon">:</span></dt>
<dd class="field-even"><p>3D twist vector</p>
</dd>
<dt class="field-odd">Return type<span class="colon">:</span></dt>
<dd class="field-odd"><p>Twist3 instance</p>
</dd>
</dl>
<p><code class="docutils literal notranslate"><span class="pre">Twist3.Tx(x)</span></code> is an se(3) translation of <code class="docutils literal notranslate"><span class="pre">x</span></code> along the x-axis</p>
<p>Example:</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</span><span class="w"> </span><span class="kn">import</span> <span class="n">Twist3</span>
<span class="gp">>>> </span><span class="n">Twist3</span><span class="o">.</span><span class="n">Tx</span><span class="p">(</span><span class="mi">2</span><span class="p">)</span>
<span class="go">Twist3([2, 0, 0, 0, 0, 0])</span>
<span class="gp">>>> </span><span class="n">Twist3</span><span class="o">.</span><span class="n">Tx</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">Twist3([</span>
<span class="go"> [2, 0, 0, 0, 0, 0],</span>
<span class="go"> [3, 0, 0, 0, 0, 0]</span>
<span class="go">])</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">transl()</span></code></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 method">
<dt class="sig sig-object py" id="spatialmath.twist.Twist3.Ty">
<em class="property"><span class="pre">classmethod</span><span class="w"> </span></em><span class="sig-name descname"><span class="pre">Ty</span></span><span class="sig-paren">(</span><em class="sig-param"><span class="n"><span class="pre">y</span></span></em><span class="sig-paren">)</span><a class="reference internal" href="_modules/spatialmath/twist.html#Twist3.Ty"><span class="viewcode-link"><span class="pre">[source]</span></span></a><a class="headerlink" href="#spatialmath.twist.Twist3.Ty" title="Permalink to this definition"></a></dt>
<dd><p>Create a new 3D twist for pure translation along the Y-axis</p>
<dl class="field-list simple">
<dt class="field-odd">Parameters<span class="colon">:</span></dt>
<dd class="field-odd"><p><strong>y</strong> (<em>float</em>) – translation distance along the Y-axis</p>
</dd>
<dt class="field-even">Returns<span class="colon">:</span></dt>
<dd class="field-even"><p>3D twist vector</p>
</dd>
<dt class="field-odd">Return type<span class="colon">:</span></dt>
<dd class="field-odd"><p>Twist3 instance</p>
</dd>
</dl>
<p><code class="docutils literal notranslate"><span class="pre">Twist3.Ty(y)</span></code> is an se(3) translation of <code class="docutils literal notranslate"><span class="pre">y</span></code> along the y-axis</p>
<p>Example:</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</span><span class="w"> </span><span class="kn">import</span> <span class="n">Twist3</span>
<span class="gp">>>> </span><span class="n">Twist3</span><span class="o">.</span><span class="n">Ty</span><span class="p">(</span><span class="mi">2</span><span class="p">)</span>
<span class="go">Twist3([0, 2, 0, 0, 0, 0])</span>
<span class="gp">>>> </span><span class="n">Twist3</span><span class="o">.</span><span class="n">Ty</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">Twist3([</span>
<span class="go"> [0, 2, 0, 0, 0, 0],</span>
<span class="go"> [0, 3, 0, 0, 0, 0]</span>
<span class="go">])</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">transl()</span></code></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 method">
<dt class="sig sig-object py" id="spatialmath.twist.Twist3.Tz">
<em class="property"><span class="pre">classmethod</span><span class="w"> </span></em><span class="sig-name descname"><span class="pre">Tz</span></span><span class="sig-paren">(</span><em class="sig-param"><span class="n"><span class="pre">z</span></span></em><span class="sig-paren">)</span><a class="reference internal" href="_modules/spatialmath/twist.html#Twist3.Tz"><span class="viewcode-link"><span class="pre">[source]</span></span></a><a class="headerlink" href="#spatialmath.twist.Twist3.Tz" title="Permalink to this definition"></a></dt>
<dd><p>Create a new 3D twist for pure translation along the Z-axis</p>
<dl class="field-list simple">
<dt class="field-odd">Parameters<span class="colon">:</span></dt>
<dd class="field-odd"><p><strong>z</strong> (<em>float</em>) – translation distance along the Z-axis</p>
</dd>
<dt class="field-even">Returns<span class="colon">:</span></dt>
<dd class="field-even"><p>3D twist vector</p>
</dd>
<dt class="field-odd">Return type<span class="colon">:</span></dt>
<dd class="field-odd"><p>Twist3 instance</p>
</dd>
</dl>
<p><code class="docutils literal notranslate"><span class="pre">Twist3.Tz(z)</span></code> is an se(3) translation of <code class="docutils literal notranslate"><span class="pre">z</span></code> along the z-axis</p>
<p>Example:</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</span><span class="w"> </span><span class="kn">import</span> <span class="n">Twist3</span>
<span class="gp">>>> </span><span class="n">Twist3</span><span class="o">.</span><span class="n">Tz</span><span class="p">(</span><span class="mi">2</span><span class="p">)</span>
<span class="go">Twist3([0, 0, 2, 0, 0, 0])</span>
<span class="gp">>>> </span><span class="n">Twist3</span><span class="o">.</span><span class="n">Tz</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">Twist3([</span>
<span class="go"> [0, 0, 2, 0, 0, 0],</span>
<span class="go"> [0, 0, 3, 0, 0, 0]</span>
<span class="go">])</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">transl()</span></code></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 method">
<dt class="sig sig-object py" id="spatialmath.twist.Twist3.UnitPrismatic">
<em class="property"><span class="pre">classmethod</span><span class="w"> </span></em><span class="sig-name descname"><span class="pre">UnitPrismatic</span></span><span class="sig-paren">(</span><em class="sig-param"><span class="n"><span class="pre">a</span></span></em><span class="sig-paren">)</span><a class="reference internal" href="_modules/spatialmath/twist.html#Twist3.UnitPrismatic"><span class="viewcode-link"><span class="pre">[source]</span></span></a><a class="headerlink" href="#spatialmath.twist.Twist3.UnitPrismatic" title="Permalink to this definition"></a></dt>
<dd><p>Construct a new 3D unit prismatic twist</p>
<dl class="field-list simple">
<dt class="field-odd">Parameters<span class="colon">:</span></dt>
<dd class="field-odd"><p><strong>a</strong> (<em>array_like</em><em>(</em><em>3</em><em>)</em>) – Twist axis or line of action</p>
</dd>
<dt class="field-even">Returns<span class="colon">:</span></dt>
<dd class="field-even"><p>a prismatic twist</p>
</dd>
<dt class="field-odd">Return type<span class="colon">:</span></dt>
<dd class="field-odd"><p>Twist instance</p>
</dd>
</dl>
<p>A prismatic twist with a line of action in the z-direction would be:</p>
<div class="highlight-pycon notranslate"><div class="highlight"><pre><span></span>
</pre></div>
</div>
</dd></dl>
<dl class="py method">
<dt class="sig sig-object py" id="spatialmath.twist.Twist3.UnitRevolute">
<em class="property"><span class="pre">classmethod</span><span class="w"> </span></em><span class="sig-name descname"><span class="pre">UnitRevolute</span></span><span class="sig-paren">(</span><em class="sig-param"><span class="n"><span class="pre">a</span></span></em>, <em class="sig-param"><span class="n"><span class="pre">q</span></span></em>, <em class="sig-param"><span class="n"><span class="pre">pitch</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/twist.html#Twist3.UnitRevolute"><span class="viewcode-link"><span class="pre">[source]</span></span></a><a class="headerlink" href="#spatialmath.twist.Twist3.UnitRevolute" title="Permalink to this definition"></a></dt>
<dd><p>Construct a new 3D rotational unit twist</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>a</strong> (<em>array_like</em><em>(</em><em>3</em><em>)</em>) – Twist axis or line of action</p></li>
<li><p><strong>q</strong> (<em>array_like</em><em>(</em><em>3</em><em>)</em>) – Point on the line of action</p></li>
<li><p><strong>p</strong> (<em>float</em><em>, </em><em>optional</em>) – pitch, defaults to None</p></li>
</ul>
</dd>
<dt class="field-even">Returns<span class="colon">:</span></dt>
<dd class="field-even"><p>a rotational or helical twist</p>
</dd>
<dt class="field-odd">Return type<span class="colon">:</span></dt>
<dd class="field-odd"><p>Twist instance</p>
</dd>
</dl>
<p>A revolute twist with a line of action in the z-direction and passing
through (1, 2, 0) would be:</p>
<div class="highlight-pycon notranslate"><div class="highlight"><pre><span></span>
</pre></div>
</div>
</dd></dl>
<dl class="py method">
<dt class="sig sig-object py" id="spatialmath.twist.Twist3.__eq__">
<span class="sig-name descname"><span class="pre">__eq__</span></span><span class="sig-paren">(</span><em class="sig-param"><span class="n"><span class="pre">right</span></span></em><span class="sig-paren">)</span><a class="headerlink" href="#spatialmath.twist.Twist3.__eq__" title="Permalink to this definition"></a></dt>
<dd><p>Overloaded <code class="docutils literal notranslate"><span class="pre">==</span></code> operator (superclass method)</p>
<dl class="field-list simple">
<dt class="field-odd">Returns<span class="colon">:</span></dt>
<dd class="field-odd"><p>Equality of two operands</p>
</dd>
<dt class="field-even">Return type<span class="colon">:</span></dt>
<dd class="field-even"><p>bool or list of bool</p>
</dd>
</dl>
<p><code class="docutils literal notranslate"><span class="pre">S1</span> <span class="pre">==</span> <span class="pre">S2</span></code> is True if <code class="docutils literal notranslate"><span class="pre">S1`</span> <span class="pre">is</span> <span class="pre">elementwise</span> <span class="pre">equal</span> <span class="pre">to</span> <span class="pre">``S2</span></code>.</p>
<p>Example:</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 'Twist3' 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 'S1' 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 'Twist3' 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 'S1' 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.twist.Twist3.__ne__" title="spatialmath.twist.Twist3.__ne__"><code class="xref py py-func docutils literal notranslate"><span class="pre">__ne__()</span></code></a></p>
</dd>
</dl>
</dd></dl>
<dl class="py method">
<dt class="sig sig-object py" id="spatialmath.twist.Twist3.__init__">
<span class="sig-name descname"><span class="pre">__init__</span></span><span class="sig-paren">(</span><em class="sig-param"><span class="n"><span class="pre">arg</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">w</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/twist.html#Twist3.__init__"><span class="viewcode-link"><span class="pre">[source]</span></span></a><a class="headerlink" href="#spatialmath.twist.Twist3.__init__" title="Permalink to this definition"></a></dt>
<dd><p>Construct a new 3D twist object</p>
<ul class="simple">
<li><p><code class="docutils literal notranslate"><span class="pre">Twist3()</span></code> is a Twist3 instance representing null motion – the
identity twist</p></li>
<li><p><code class="docutils literal notranslate"><span class="pre">Twist3(S)</span></code> is a Twist3 instance from an array-like (6,)</p></li>
<li><p><code class="docutils literal notranslate"><span class="pre">Twist3(v,</span> <span class="pre">w)</span></code> is a Twist3 instance from a moment <code class="docutils literal notranslate"><span class="pre">v</span></code> (3,) and
direction <code class="docutils literal notranslate"><span class="pre">w</span></code> (3,)</p></li>
<li><p><code class="docutils literal notranslate"><span class="pre">Twist3([S1,</span> <span class="pre">S2,</span> <span class="pre">...</span> <span class="pre">SN])</span></code> where each <code class="docutils literal notranslate"><span class="pre">Si</span></code> is a numpy array (6,)</p></li>
<li><p><code class="docutils literal notranslate"><span class="pre">Twist3(X)</span></code> is a Twist3 instance with the same value as <code class="docutils literal notranslate"><span class="pre">X</span></code>, ie.
a copy</p></li>
<li><p><code class="docutils literal notranslate"><span class="pre">Twist3([X1,</span> <span class="pre">X2,</span> <span class="pre">...</span> <span class="pre">XN])</span></code> where each Xi is a Twist3 instance, is a
Twist3 instance containing N motions</p></li>
</ul>
</dd></dl>
<dl class="py method">
<dt class="sig sig-object py" id="spatialmath.twist.Twist3.__mul__">
<span class="sig-name descname"><span class="pre">__mul__</span></span><span class="sig-paren">(</span><em class="sig-param"><span class="n"><span class="pre">right</span></span></em><span class="sig-paren">)</span><a class="reference internal" href="_modules/spatialmath/twist.html#Twist3.__mul__"><span class="viewcode-link"><span class="pre">[source]</span></span></a><a class="headerlink" href="#spatialmath.twist.Twist3.__mul__" title="Permalink to this definition"></a></dt>
<dd><p>Overloaded <code class="docutils literal notranslate"><span class="pre">*</span></code> operator</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>left</strong> – left multiplicand</p></li>
<li><p><strong>right</strong> – right multiplicand</p></li>
</ul>
</dd>
<dt class="field-even">Returns<span class="colon">:</span></dt>
<dd class="field-even"><p>product</p>
</dd>
<dt class="field-odd">Raises<span class="colon">:</span></dt>
<dd class="field-odd"><p>ValueError</p>
</dd>
</dl>
<p>Twist composition or scaling:</p>
<ul class="simple">
<li><p><code class="docutils literal notranslate"><span class="pre">X</span> <span class="pre">*</span> <span class="pre">Y</span></code> compounds the twists <code class="docutils literal notranslate"><span class="pre">X</span></code> and <code class="docutils literal notranslate"><span class="pre">Y</span></code></p></li>
<li><p><code class="docutils literal notranslate"><span class="pre">X</span> <span class="pre">*</span> <span class="pre">s</span></code> performs elementwise multiplication of the elements of <code class="docutils literal notranslate"><span class="pre">X</span></code> by <code class="docutils literal notranslate"><span class="pre">s</span></code></p></li>
<li><p><code class="docutils literal notranslate"><span class="pre">s</span> <span class="pre">*</span> <span class="pre">X</span></code> performs elementwise multiplication of the elements of <code class="docutils literal notranslate"><span class="pre">X</span></code> by <code class="docutils literal notranslate"><span class="pre">s</span></code></p></li>
</ul>
<table class="docutils align-default">
<thead>
<tr class="row-odd"><th class="head" colspan="2"><p>Multiplicands</p></th>
<th class="head" colspan="2"><p>Product</p></th>
</tr>
<tr class="row-even"><th class="head"><p>left</p></th>
<th class="head"><p>right</p></th>
<th class="head"><p>type</p></th>
<th class="head"><p>operation</p></th>
</tr>
</thead>
<tbody>
<tr class="row-odd"><td><p>Twist3</p></td>
<td><p>Twist3</p></td>
<td><p>Twist3</p></td>
<td><p>product of exponentials</p></td>
</tr>
<tr class="row-even"><td><p>Twist3</p></td>
<td><p>scalar</p></td>
<td><p>Twist3</p></td>
<td><p>element-wise product</p></td>
</tr>
<tr class="row-odd"><td><p>scalar</p></td>
<td><p>Twist3</p></td>
<td><p>Twist3</p></td>
<td><p>element-wise product</p></td>
</tr>
<tr class="row-even"><td><p>Twist3</p></td>
<td><p>SE3</p></td>
<td><p>Twist3</p></td>
<td><p>exponential x SE3</p></td>
</tr>
</tbody>
</table>
<div class="admonition note">
<p class="admonition-title">Note</p>
<ol class="arabic simple">
<li><p>scalar x Twist is handled by <code class="docutils literal notranslate"><span class="pre">__rmul__</span></code></p></li>
</ol>
<p>#. scalar multiplication is commutative but the result is not a group
operation so the result will be a matrix
#. Any other input combinations result in a ValueError.</p>
</div>
<p>For pose composition the <code class="docutils literal notranslate"><span class="pre">left</span></code> and <code class="docutils literal notranslate"><span class="pre">right</span></code> operands may be a sequence</p>
<table class="docutils align-default">
<thead>
<tr class="row-odd"><th class="head"><p>len(left)</p></th>
<th class="head"><p>len(right)</p></th>
<th class="head"><p>len</p></th>
<th class="head"><p>operation</p></th>
</tr>
</thead>
<tbody>
<tr class="row-even"><td><p>1</p></td>
<td><p>1</p></td>
<td><p>1</p></td>
<td><p><code class="docutils literal notranslate"><span class="pre">prod</span> <span class="pre">=</span> <span class="pre">left</span> <span class="pre">*</span> <span class="pre">right</span></code></p></td>
</tr>
<tr class="row-odd"><td><p>1</p></td>
<td><p>M</p></td>
<td><p>M</p></td>
<td><p><code class="docutils literal notranslate"><span class="pre">prod[i]</span> <span class="pre">=</span> <span class="pre">left</span> <span class="pre">*</span> <span class="pre">right[i]</span></code></p></td>
</tr>
<tr class="row-even"><td><p>N</p></td>
<td><p>1</p></td>
<td><p>M</p></td>
<td><p><code class="docutils literal notranslate"><span class="pre">prod[i]</span> <span class="pre">=</span> <span class="pre">left[i]</span> <span class="pre">*</span> <span class="pre">right</span></code></p></td>
</tr>
<tr class="row-odd"><td><p>M</p></td>
<td><p>M</p></td>
<td><p>M</p></td>
<td><p><code class="docutils literal notranslate"><span class="pre">prod[i]</span> <span class="pre">=</span> <span class="pre">left[i]</span> <span class="pre">*</span> <span class="pre">right[i]</span></code></p></td>
</tr>
</tbody>
</table>
</dd></dl>
<dl class="py method">
<dt class="sig sig-object py" id="spatialmath.twist.Twist3.__ne__">
<span class="sig-name descname"><span class="pre">__ne__</span></span><span class="sig-paren">(</span><em class="sig-param"><span class="n"><span class="pre">right</span></span></em><span class="sig-paren">)</span><a class="headerlink" href="#spatialmath.twist.Twist3.__ne__" title="Permalink to this definition"></a></dt>
<dd><p>Overloaded <code class="docutils literal notranslate"><span class="pre">!=</span></code> operator (superclass method)</p>
<dl class="field-list simple">
<dt class="field-odd">Return type<span class="colon">:</span></dt>
<dd class="field-odd"><p>bool</p>
</dd>
</dl>
<p><code class="docutils literal notranslate"><span class="pre">S1</span> <span class="pre">==</span> <span class="pre">S2</span></code> is True if <code class="docutils literal notranslate"><span class="pre">S1`</span> <span class="pre">is</span> <span class="pre">not</span> <span class="pre">elementwise</span> <span class="pre">equal</span> <span class="pre">to</span> <span class="pre">``S2</span></code>.</p>
<p>Example:</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</span><span class="w"> </span><span class="kn">import</span> <span class="n">Twist3</span>
<span class="gp">>>> </span><span class="n">S1</span> <span class="o">=</span> <span class="n">Twist3</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="mi">4</span><span class="p">,</span><span class="mi">5</span><span class="p">,</span><span class="mi">6</span><span class="p">])</span>
<span class="gp">>>> </span><span class="n">S2</span> <span class="o">=</span> <span class="n">Twist3</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="mi">4</span><span class="p">,</span><span class="mi">5</span><span class="p">,</span><span class="mi">6</span><span class="p">])</span>
<span class="gp">>>> </span><span class="n">S1</span> <span class="o">!=</span> <span class="n">S2</span>
<span class="go">False</span>
<span class="gp">>>> </span><span class="n">S2</span> <span class="o">=</span> <span class="n">Twist3</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="mi">4</span><span class="p">,</span><span class="mi">5</span><span class="p">,</span><span class="mi">7</span><span class="p">])</span>
<span class="gp">>>> </span><span class="n">S1</span> <span class="o">!=</span> <span class="n">S2</span>
<span class="go">True</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.twist.Twist3.__ne__" title="spatialmath.twist.Twist3.__ne__"><code class="xref py py-func docutils literal notranslate"><span class="pre">__ne__()</span></code></a></p>
</dd>
</dl>
</dd></dl>
<dl class="py method">
<dt class="sig sig-object py" id="spatialmath.twist.Twist3.__truediv__">
<span class="sig-name descname"><span class="pre">__truediv__</span></span><span class="sig-paren">(</span><em class="sig-param"><span class="n"><span class="pre">right</span></span></em><span class="sig-paren">)</span><a class="headerlink" href="#spatialmath.twist.Twist3.__truediv__" title="Permalink to this definition"></a></dt>
<dd></dd></dl>
<dl class="py method">
<dt class="sig sig-object py" id="spatialmath.twist.Twist3.ad">
<span class="sig-name descname"><span class="pre">ad</span></span><span class="sig-paren">(</span><span class="sig-paren">)</span><a class="reference internal" href="_modules/spatialmath/twist.html#Twist3.ad"><span class="viewcode-link"><span class="pre">[source]</span></span></a><a class="headerlink" href="#spatialmath.twist.Twist3.ad" title="Permalink to this definition"></a></dt>
<dd><p>Logarithm of adjoint of 3D twist</p>
<dl class="field-list simple">
<dt class="field-odd">Returns<span class="colon">:</span></dt>
<dd class="field-odd"><p>logarithm of adjoint matrix</p>
</dd>
<dt class="field-even">Return type<span class="colon">:</span></dt>
<dd class="field-even"><p>ndarray(6,6)</p>
</dd>
</dl>
<p><code class="docutils literal notranslate"><span class="pre">S.ad()</span></code> is the 6x6 logarithm of the adjoint matrix of the
corresponding homogeneous transformation.</p>
<p>For a twist representing motion from frame {B} to {A}, the adjoint will
transform a twist relative to frame {A} to one relative to frame {B}.</p>
<p>Example:</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</span><span class="w"> </span><span class="kn">import</span> <span class="n">Twist3</span>
<span class="gp">>>> </span><span class="n">S</span> <span class="o">=</span> <span class="n">Twist3</span><span class="o">.</span><span class="n">Rx</span><span class="p">(</span><span class="mf">0.3</span><span class="p">)</span>
<span class="gp">>>> </span><span class="n">S</span><span class="o">.</span><span class="n">ad</span><span class="p">()</span>
<span class="go">array([[ 0. , -0. , 0. , 0. , -0. , 0. ],</span>
<span class="go"> [ 0. , 0. , -0.3, 0. , 0. , -0. ],</span>
<span class="go"> [-0. , 0.3, 0. , -0. , 0. , 0. ],</span>
<span class="go"> [ 0. , 0. , 0. , 0. , -0. , 0. ],</span>
<span class="go"> [ 0. , 0. , 0. , 0. , 0. , -0.3],</span>
<span class="go"> [ 0. , 0. , 0. , -0. , 0.3, 0. ]])</span>
</pre></div>
</div>
<div class="admonition note">
<p class="admonition-title">Note</p>
<p>An alternative approach to computing the adjoint is to exponentiate this 6x6
matrix.</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.twist.Twist3.Ad" title="spatialmath.twist.Twist3.Ad"><code class="xref py py-func docutils literal notranslate"><span class="pre">Twist3.Ad()</span></code></a></p>
</dd>
</dl>
</dd></dl>
<dl class="py method">
<dt class="sig sig-object py" id="spatialmath.twist.Twist3.append">
<span class="sig-name descname"><span class="pre">append</span></span><span class="sig-paren">(</span><em class="sig-param"><span class="n"><span class="pre">item</span></span></em><span class="sig-paren">)</span><a class="headerlink" href="#spatialmath.twist.Twist3.append" title="Permalink to this definition"></a></dt>
<dd><p>Append a value to an instance (BasePoseList superclass method)</p>
<dl class="field-list simple">
<dt class="field-odd">Parameters<span class="colon">:</span></dt>
<dd class="field-odd"><p><strong>x</strong> (<a class="reference internal" href="3d_quaternion.html#spatialmath.quaternion.Quaternion" title="spatialmath.quaternion.Quaternion"><em>Quaternion</em></a><em> or </em><em>UnitQuaternion instance</em>) – the value to append</p>
</dd>
<dt class="field-even">Raises<span class="colon">:</span></dt>
<dd class="field-even"><p><strong>ValueError</strong> – incorrect type of appended object</p>
</dd>
<dt class="field-odd">Return type<span class="colon">:</span></dt>
<dd class="field-odd"><p><span class="sphinx_autodoc_typehints-type"><code class="xref py py-obj docutils literal notranslate"><span class="pre">None</span></code></span></p>
</dd>
</dl>
<p>Appends the argument to the object’s internal list of values.</p>
<p>Example:</p>
<div class="highlight-default notranslate"><div class="highlight"><pre><span></span><span class="gp">>>> </span><span class="n">x</span> <span class="o">=</span> <span class="n">X</span><span class="o">.</span><span class="n">Alloc</span><span class="p">(</span><span class="mi">10</span><span class="p">)</span>
<span class="gp">>>> </span><span class="nb">len</span><span class="p">(</span><span class="n">x</span><span class="p">)</span>
<span class="go">10</span>
<span class="gp">>>> </span><span class="n">x</span><span class="o">.</span><span class="n">append</span><span class="p">(</span><span class="n">X</span><span class="p">())</span> <span class="c1"># append to the list</span>
<span class="gp">>>> </span><span class="nb">len</span><span class="p">(</span><span class="n">x</span><span class="p">)</span>
<span class="go">11</span>
</pre></div>
</div>
<p>where <code class="docutils literal notranslate"><span class="pre">X</span></code> is any of the SMTB classes.</p>
</dd></dl>
<dl class="py method">
<dt class="sig sig-object py" id="spatialmath.twist.Twist3.clear">
<span class="sig-name descname"><span class="pre">clear</span></span><span class="sig-paren">(</span><span class="sig-paren">)</span> <span class="sig-return"><span class="sig-return-icon">→</span> <span class="sig-return-typehint"><span class="pre">None</span> <span class="pre">--</span> <span class="pre">remove</span> <span class="pre">all</span> <span class="pre">items</span> <span class="pre">from</span> <span class="pre">S</span></span></span><a class="headerlink" href="#spatialmath.twist.Twist3.clear" title="Permalink to this definition"></a></dt>
<dd></dd></dl>
<dl class="py method">
<dt class="sig sig-object py" id="spatialmath.twist.Twist3.exp">
<span class="sig-name descname"><span class="pre">exp</span></span><span class="sig-paren">(</span><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">1</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/twist.html#Twist3.exp"><span class="viewcode-link"><span class="pre">[source]</span></span></a><a class="headerlink" href="#spatialmath.twist.Twist3.exp" title="Permalink to this definition"></a></dt>
<dd><p>Exponentiate a 3D twist</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><em>, </em><em>optional</em>) – rotation magnitude, defaults to None</p></li>
<li><p><strong>units</strong> (<em>str</em><em>, </em><em>optional</em>) – rotational units, defaults to ‘rad’</p></li>
</ul>
</dd>
<dt class="field-even">Returns<span class="colon">:</span></dt>
<dd class="field-even"><p>SE(3) matrix</p>
</dd>
<dt class="field-odd">Return type<span class="colon">:</span></dt>
<dd class="field-odd"><p>SE3 instance</p>
</dd>
</dl>
<ul class="simple">
<li><p><code class="docutils literal notranslate"><span class="pre">X.exp()</span></code> is the homogeneous transformation equivalent to the twist,
<span class="math notranslate nohighlight">\(e^{[S]}\)</span></p></li>
<li><p><code class="docutils literal notranslate"><span class="pre">X.exp(θ)</span> <span class="pre">as</span> <span class="pre">above</span> <span class="pre">but</span> <span class="pre">with</span> <span class="pre">a</span> <span class="pre">rotation</span> <span class="pre">of</span> <span class="pre">``θ</span></code> about the twist axis,
<span class="math notranslate nohighlight">\(e^{ heta[S]}\)</span></p></li>
</ul>
<p>If <code class="docutils literal notranslate"><span class="pre">len(X)==1</span></code> and <code class="docutils literal notranslate"><span class="pre">len(θ)==N</span></code> then the resulting SE3 object has
<code class="docutils literal notranslate"><span class="pre">N</span></code> values equivalent to the twist <span class="math notranslate nohighlight">\(e^{ heta_i[S]}\)</span>.</p>
<p>If <code class="docutils literal notranslate"><span class="pre">len(X)==N</span></code> and <code class="docutils literal notranslate"><span class="pre">len(θ)==1</span></code> then the resulting SE3 object has
<code class="docutils literal notranslate"><span class="pre">N</span></code> values equivalent to the twist <span class="math notranslate nohighlight">\(e^{ heta[S_i]}\)</span>.</p>
<p>If <code class="docutils literal notranslate"><span class="pre">len(X)==N</span></code> and <code class="docutils literal notranslate"><span class="pre">len(θ)==N</span></code> then the resulting SE3 object has
<code class="docutils literal notranslate"><span class="pre">N</span></code> values equivalent to the twist <span class="math notranslate nohighlight">\(e^{ heta_i[S_i]}\)</span>.</p>
<p>Example:</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</span><span class="w"> </span><span class="kn">import</span> <span class="n">SE3</span><span class="p">,</span> <span class="n">Twist3</span>
<span class="gp">>>> </span><span class="n">T</span> <span class="o">=</span> <span class="n">SE3</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="o">*</span> <span class="n">SE3</span><span class="o">.</span><span class="n">Rx</span><span class="p">(</span><span class="mf">0.3</span><span class="p">)</span>
<span class="gp">>>> </span><span class="n">S</span> <span class="o">=</span> <span class="n">Twist3</span><span class="p">(</span><span class="n">T</span><span class="p">)</span>
<span class="gp">>>> </span><span class="n">S</span><span class="o">.</span><span class="n">exp</span><span class="p">(</span><span class="mi">0</span><span class="p">)</span>
<span class="go">SE3(array([[1., 0., 0., 0.],</span>
<span class="go"> [0., 1., 0., 0.],</span>
<span class="go"> [0., 0., 1., 0.],</span>
<span class="go"> [0., 0., 0., 1.]]))</span>
<span class="gp">>>> </span><span class="n">S</span><span class="o">.</span><span class="n">exp</span><span class="p">(</span><span class="mi">1</span><span class="p">)</span>
<span class="go">SE3(array([[ 1. , 0. , 0. , 1. ],</span>
<span class="go"> [ 0. , 0.9553, -0.2955, 2. ],</span>
<span class="go"> [ 0. , 0.2955, 0.9553, 3. ],</span>
<span class="go"> [ 0. , 0. , 0. , 1. ]]))</span>
</pre></div>
</div>
<div class="admonition note">
<p class="admonition-title">Note</p>
<ul class="simple">
<li><p>For the second form, the twist must, if rotational, have a unit
rotational component.</p></li>
</ul>
</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">spatialmath.smb.trexp()</span></code></p>
</dd>
</dl>
</dd></dl>
<dl class="py method">
<dt class="sig sig-object py" id="spatialmath.twist.Twist3.extend">
<span class="sig-name descname"><span class="pre">extend</span></span><span class="sig-paren">(</span><em class="sig-param"><span class="n"><span class="pre">iterable</span></span></em><span class="sig-paren">)</span><a class="headerlink" href="#spatialmath.twist.Twist3.extend" title="Permalink to this definition"></a></dt>
<dd><p>Extend sequence of values in an instance (BasePoseList superclass method)</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>instance</em><em> of </em><em>same type</em>) – the value to extend</p>
</dd>
<dt class="field-even">Raises<span class="colon">:</span></dt>
<dd class="field-even"><p><strong>ValueError</strong> – incorrect type of appended object</p>
</dd>
<dt class="field-odd">Return type<span class="colon">:</span></dt>
<dd class="field-odd"><p><span class="sphinx_autodoc_typehints-type"><code class="xref py py-obj docutils literal notranslate"><span class="pre">None</span></code></span></p>
</dd>
</dl>
<p>Appends the argument’s values to the object’s internal list of values.</p>
<p>Example:</p>
<div class="highlight-default notranslate"><div class="highlight"><pre><span></span><span class="gp">>>> </span><span class="n">x</span> <span class="o">=</span> <span class="n">X</span><span class="o">.</span><span class="n">Alloc</span><span class="p">(</span><span class="mi">10</span><span class="p">)</span>
<span class="gp">>>> </span><span class="nb">len</span><span class="p">(</span><span class="n">x</span><span class="p">)</span>
<span class="go">10</span>
<span class="gp">>>> </span><span class="n">x</span><span class="o">.</span><span class="n">append</span><span class="p">(</span><span class="n">X</span><span class="o">.</span><span class="n">Alloc</span><span class="p">(</span><span class="mi">5</span><span class="p">))</span> <span class="c1"># extend the list</span>
<span class="gp">>>> </span><span class="nb">len</span><span class="p">(</span><span class="n">x</span><span class="p">)</span>