|
|
|
|
|
<!DOCTYPE html> |
|
|
|
<html class="no-js" lang="en" > |
|
<head> |
|
<meta charset="utf-8"> |
|
|
|
<meta name="viewport" content="width=device-width, initial-scale=1.0"> |
|
|
|
<title>liegroups — Lie Groups 1.1.0 documentation</title> |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
<script type="text/javascript" src="_static/js/modernizr.min.js"></script> |
|
|
|
|
|
<script type="text/javascript" id="documentation_options" data-url_root="./" src="_static/documentation_options.js"></script> |
|
<script type="text/javascript" src="_static/jquery.js"></script> |
|
<script type="text/javascript" src="_static/underscore.js"></script> |
|
<script type="text/javascript" src="_static/doctools.js"></script> |
|
<script type="text/javascript" src="_static/language_data.js"></script> |
|
<script async="async" type="text/javascript" src="https://cdnjs.cloudflare.com/ajax/libs/mathjax/2.7.5/latest.js?config=TeX-AMS-MML_HTMLorMML"></script> |
|
|
|
<script type="text/javascript" src="_static/js/theme.js"></script> |
|
|
|
|
|
|
|
|
|
<link rel="stylesheet" href="_static/css/theme.css" type="text/css" /> |
|
<link rel="stylesheet" href="_static/pygments.css" type="text/css" /> |
|
<link rel="index" title="Index" href="genindex.html" /> |
|
<link rel="search" title="Search" href="search.html" /> |
|
<link rel="next" title="liegroups.torch" href="torch.html" /> |
|
<link rel="prev" title="Lie Groups" href="index.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"> Lie Groups |
|
|
|
|
|
|
|
</a> |
|
|
|
|
|
|
|
|
|
<div class="version"> |
|
1.1.0 |
|
</div> |
|
|
|
|
|
|
|
|
|
<div role="search"> |
|
<form id="rtd-search-form" class="wy-form" action="search.html" method="get"> |
|
<input type="text" name="q" placeholder="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="main navigation"> |
|
|
|
|
|
|
|
|
|
|
|
|
|
<ul class="current"> |
|
<li class="toctree-l1 current"><a class="current reference internal" href="#">liegroups</a><ul> |
|
<li class="toctree-l2"><a class="reference internal" href="#so-2">SO(2)</a></li> |
|
<li class="toctree-l2"><a class="reference internal" href="#se-2">SE(2)</a></li> |
|
<li class="toctree-l2"><a class="reference internal" href="#so-3">SO(3)</a></li> |
|
<li class="toctree-l2"><a class="reference internal" href="#se-3">SE(3)</a></li> |
|
</ul> |
|
</li> |
|
<li class="toctree-l1"><a class="reference internal" href="torch.html">liegroups.torch</a></li> |
|
</ul> |
|
|
|
|
|
|
|
</div> |
|
</div> |
|
</nav> |
|
|
|
<section data-toggle="wy-nav-shift" class="wy-nav-content-wrap"> |
|
|
|
|
|
<nav class="wy-nav-top" aria-label="top navigation"> |
|
|
|
<i data-toggle="wy-nav-top" class="fa fa-bars"></i> |
|
<a href="index.html">Lie Groups</a> |
|
|
|
</nav> |
|
|
|
|
|
<div class="wy-nav-content"> |
|
|
|
<div class="rst-content"> |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
<div role="navigation" aria-label="breadcrumbs navigation"> |
|
|
|
<ul class="wy-breadcrumbs"> |
|
|
|
<li><a href="index.html">Docs</a> »</li> |
|
|
|
<li>liegroups</li> |
|
|
|
|
|
<li class="wy-breadcrumbs-aside"> |
|
|
|
|
|
<a href="_sources/numpy.rst.txt" rel="nofollow"> View page source</a> |
|
|
|
|
|
</li> |
|
|
|
</ul> |
|
|
|
|
|
<hr/> |
|
</div> |
|
<div role="main" class="document" itemscope="itemscope" itemtype="http://schema.org/Article"> |
|
<div itemprop="articleBody"> |
|
|
|
<div class="section" id="liegroups"> |
|
<h1>liegroups<a class="headerlink" href="#liegroups" title="Permalink to this headline">¶</a></h1> |
|
<p>The default implementation uses numpy as the backend linear algebra library.</p> |
|
<div class="section" id="so-2"> |
|
<h2>SO(2)<a class="headerlink" href="#so-2" title="Permalink to this headline">¶</a></h2> |
|
<dl class="attribute"> |
|
<dt id="liegroups.SO2"> |
|
<code class="sig-prename descclassname">liegroups.</code><code class="sig-name descname">SO2</code><a class="headerlink" href="#liegroups.SO2" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>alias of <a class="reference internal" href="#liegroups.numpy.so2.SO2Matrix" title="liegroups.numpy.so2.SO2Matrix"><code class="xref py py-class docutils literal notranslate"><span class="pre">liegroups.numpy.so2.SO2Matrix</span></code></a></p> |
|
</dd></dl> |
|
|
|
<dl class="class"> |
|
<dt id="liegroups.numpy.so2.SO2Matrix"> |
|
<em class="property">class </em><code class="sig-prename descclassname">liegroups.numpy.so2.</code><code class="sig-name descname">SO2Matrix</code><span class="sig-paren">(</span><em class="sig-param">mat</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.so2.SO2Matrix" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Rotation matrix in <span class="math notranslate nohighlight">\(SO(2)\)</span> using active (alibi) transformations.</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\begin{split}SO(2) &= \left\{ \mathbf{C} \in \mathbb{R}^{2 \times 2} ~\middle|~ \mathbf{C}\mathbf{C}^T = \mathbf{1}, \det \mathbf{C} = 1 \right\} \\ |
|
\mathfrak{so}(2) &= \left\{ \boldsymbol{\Phi} = \phi^\wedge \in \mathbb{R}^{2 \times 2} ~\middle|~ \phi \in \mathbb{R} \right\}\end{split}\]</div> |
|
<dl class="field-list simple"> |
|
<dt class="field-odd">Variables</dt> |
|
<dd class="field-odd"><ul class="simple"> |
|
<li><p><strong>dim</strong> – Dimension of the rotation matrix.</p></li> |
|
<li><p><strong>dof</strong> – Underlying degrees of freedom (i.e., dimension of the tangent space).</p></li> |
|
<li><p><strong>mat</strong> – Storage for the rotation matrix <span class="math notranslate nohighlight">\(\mathbf{C}\)</span>.</p></li> |
|
</ul> |
|
</dd> |
|
</dl> |
|
<dl class="method"> |
|
<dt id="liegroups.numpy.so2.SO2Matrix.adjoint"> |
|
<code class="sig-name descname">adjoint</code><span class="sig-paren">(</span><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.so2.SO2Matrix.adjoint" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Adjoint matrix of the transformation.</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\text{Ad}(\mathbf{C}) = 1\]</div> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.so2.SO2Matrix.as_matrix"> |
|
<code class="sig-name descname">as_matrix</code><span class="sig-paren">(</span><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.so2.SO2Matrix.as_matrix" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Return the matrix representation of the rotation.</p> |
|
</dd></dl> |
|
|
|
<dl class="attribute"> |
|
<dt id="liegroups.numpy.so2.SO2Matrix.dim"> |
|
<code class="sig-name descname">dim</code><em class="property"> = 2</em><a class="headerlink" href="#liegroups.numpy.so2.SO2Matrix.dim" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Dimension of the transformation matrix.</p> |
|
</dd></dl> |
|
|
|
<dl class="attribute"> |
|
<dt id="liegroups.numpy.so2.SO2Matrix.dof"> |
|
<code class="sig-name descname">dof</code><em class="property"> = 1</em><a class="headerlink" href="#liegroups.numpy.so2.SO2Matrix.dof" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Underlying degrees of freedom (i.e., dimension of the tangent space).</p> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.so2.SO2Matrix.dot"> |
|
<code class="sig-name descname">dot</code><span class="sig-paren">(</span><em class="sig-param">other</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.so2.SO2Matrix.dot" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Multiply another rotation or one or more vectors on the left.</p> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.so2.SO2Matrix.exp"> |
|
<em class="property">classmethod </em><code class="sig-name descname">exp</code><span class="sig-paren">(</span><em class="sig-param">phi</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.so2.SO2Matrix.exp" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Exponential map for <span class="math notranslate nohighlight">\(SO(2)\)</span>, which computes a transformation from a tangent vector:</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\begin{split}\mathbf{C}(\phi) = |
|
\exp(\phi^\wedge) = |
|
\cos \phi \mathbf{1} + \sin \phi 1^\wedge = |
|
\begin{bmatrix} |
|
\cos \phi & -\sin \phi \\ |
|
\sin \phi & \cos \phi |
|
\end{bmatrix}\end{split}\]</div> |
|
<p>This is the inverse operation to <code class="xref py py-meth docutils literal notranslate"><span class="pre">log()</span></code>.</p> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.so2.SO2Matrix.from_angle"> |
|
<em class="property">classmethod </em><code class="sig-name descname">from_angle</code><span class="sig-paren">(</span><em class="sig-param">angle_in_radians</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.so2.SO2Matrix.from_angle" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Form a rotation matrix given an angle in radians.</p> |
|
<p>See <code class="xref py py-meth docutils literal notranslate"><span class="pre">exp()</span></code></p> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.so2.SO2Matrix.from_matrix"> |
|
<em class="property">classmethod </em><code class="sig-name descname">from_matrix</code><span class="sig-paren">(</span><em class="sig-param">mat</em>, <em class="sig-param">normalize=False</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.so2.SO2Matrix.from_matrix" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Create a rotation from a matrix (safe, but slower).</p> |
|
<p>Throws an error if mat is invalid and normalize=False. |
|
If normalize=True invalid matrices will be normalized to be valid.</p> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.so2.SO2Matrix.identity"> |
|
<em class="property">classmethod </em><code class="sig-name descname">identity</code><span class="sig-paren">(</span><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.so2.SO2Matrix.identity" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Return the identity rotation.</p> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.so2.SO2Matrix.inv"> |
|
<code class="sig-name descname">inv</code><span class="sig-paren">(</span><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.so2.SO2Matrix.inv" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Return the inverse rotation:</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\mathbf{C}^{-1} = \mathbf{C}^T\]</div> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.so2.SO2Matrix.inv_left_jacobian"> |
|
<em class="property">classmethod </em><code class="sig-name descname">inv_left_jacobian</code><span class="sig-paren">(</span><em class="sig-param">phi</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.so2.SO2Matrix.inv_left_jacobian" title="Permalink to this definition">¶</a></dt> |
|
<dd><p><span class="math notranslate nohighlight">\(SO(2)\)</span> inverse left Jacobian.</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\begin{split}\mathbf{J}^{-1}(\phi) = |
|
\begin{cases} |
|
\mathbf{1} - \frac{1}{2} \phi^\wedge, & \text{if } \phi \text{ is small} \\ |
|
\frac{\phi}{2} \cot \frac{\phi}{2} \mathbf{1} - |
|
\frac{\phi}{2} 1^\wedge, & \text{otherwise} |
|
\end{cases}\end{split}\]</div> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.so2.SO2Matrix.is_valid_matrix"> |
|
<em class="property">classmethod </em><code class="sig-name descname">is_valid_matrix</code><span class="sig-paren">(</span><em class="sig-param">mat</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.so2.SO2Matrix.is_valid_matrix" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Check if a matrix is a valid rotation matrix.</p> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.so2.SO2Matrix.left_jacobian"> |
|
<em class="property">classmethod </em><code class="sig-name descname">left_jacobian</code><span class="sig-paren">(</span><em class="sig-param">phi</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.so2.SO2Matrix.left_jacobian" title="Permalink to this definition">¶</a></dt> |
|
<dd><p><span class="math notranslate nohighlight">\(SO(2)\)</span> left Jacobian.</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\begin{split}\mathbf{J}(\phi) = |
|
\begin{cases} |
|
\mathbf{1} + \frac{1}{2} \phi^\wedge, & \text{if } \phi \text{ is small} \\ |
|
\frac{\sin \phi}{\phi} \mathbf{1} - |
|
\frac{1 - \cos \phi}{\phi} 1^\wedge, & \text{otherwise} |
|
\end{cases}\end{split}\]</div> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.so2.SO2Matrix.log"> |
|
<code class="sig-name descname">log</code><span class="sig-paren">(</span><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.so2.SO2Matrix.log" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Logarithmic map for <span class="math notranslate nohighlight">\(SO(2)\)</span>, which computes a tangent vector from a transformation:</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\phi(\mathbf{C}) = |
|
\ln(\mathbf{C})^\vee = |
|
\text{atan2}(C_{1,0}, C_{0,0})\]</div> |
|
<p>This is the inverse operation to <code class="xref py py-meth docutils literal notranslate"><span class="pre">exp()</span></code>.</p> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.so2.SO2Matrix.normalize"> |
|
<code class="sig-name descname">normalize</code><span class="sig-paren">(</span><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.so2.SO2Matrix.normalize" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Normalize the rotation matrix to ensure it is valid and |
|
negate the effect of rounding errors.</p> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.so2.SO2Matrix.perturb"> |
|
<code class="sig-name descname">perturb</code><span class="sig-paren">(</span><em class="sig-param">phi</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.so2.SO2Matrix.perturb" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Perturb the rotation in-place on the left by a vector in its local tangent space.</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\mathbf{C} \gets \exp(\boldsymbol{\phi}^\wedge) \mathbf{C}\]</div> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.so2.SO2Matrix.to_angle"> |
|
<code class="sig-name descname">to_angle</code><span class="sig-paren">(</span><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.so2.SO2Matrix.to_angle" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Recover the rotation angle in radians from the rotation matrix.</p> |
|
<p>See <code class="xref py py-meth docutils literal notranslate"><span class="pre">log()</span></code></p> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.so2.SO2Matrix.vee"> |
|
<em class="property">classmethod </em><code class="sig-name descname">vee</code><span class="sig-paren">(</span><em class="sig-param">Phi</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.so2.SO2Matrix.vee" title="Permalink to this definition">¶</a></dt> |
|
<dd><p><span class="math notranslate nohighlight">\(SO(2)\)</span> vee operator as defined by Barfoot.</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\phi = \boldsymbol{\Phi}^\vee\]</div> |
|
<p>This is the inverse operation to <code class="xref py py-meth docutils literal notranslate"><span class="pre">wedge()</span></code>.</p> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.so2.SO2Matrix.wedge"> |
|
<em class="property">classmethod </em><code class="sig-name descname">wedge</code><span class="sig-paren">(</span><em class="sig-param">phi</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.so2.SO2Matrix.wedge" title="Permalink to this definition">¶</a></dt> |
|
<dd><p><span class="math notranslate nohighlight">\(SO(2)\)</span> wedge operator as defined by Barfoot.</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\begin{split}\boldsymbol{\Phi} = |
|
\phi^\wedge = |
|
\begin{bmatrix} |
|
0 & -\phi \\ |
|
\phi & 0 |
|
\end{bmatrix}\end{split}\]</div> |
|
<p>This is the inverse operation to <code class="xref py py-meth docutils literal notranslate"><span class="pre">vee()</span></code>.</p> |
|
</dd></dl> |
|
|
|
</dd></dl> |
|
|
|
</div> |
|
<div class="section" id="se-2"> |
|
<h2>SE(2)<a class="headerlink" href="#se-2" title="Permalink to this headline">¶</a></h2> |
|
<dl class="attribute"> |
|
<dt id="liegroups.SE2"> |
|
<code class="sig-prename descclassname">liegroups.</code><code class="sig-name descname">SE2</code><a class="headerlink" href="#liegroups.SE2" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>alias of <a class="reference internal" href="#liegroups.numpy.se2.SE2Matrix" title="liegroups.numpy.se2.SE2Matrix"><code class="xref py py-class docutils literal notranslate"><span class="pre">liegroups.numpy.se2.SE2Matrix</span></code></a></p> |
|
</dd></dl> |
|
|
|
<dl class="class"> |
|
<dt id="liegroups.numpy.se2.SE2Matrix"> |
|
<em class="property">class </em><code class="sig-prename descclassname">liegroups.numpy.se2.</code><code class="sig-name descname">SE2Matrix</code><span class="sig-paren">(</span><em class="sig-param">rot</em>, <em class="sig-param">trans</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.se2.SE2Matrix" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Homogeneous transformation matrix in <span class="math notranslate nohighlight">\(SE(2)\)</span> using active (alibi) transformations.</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\begin{split}SE(2) &= \left\{ \mathbf{T}= |
|
\begin{bmatrix} |
|
\mathbf{C} & \mathbf{r} \\ |
|
\mathbf{0}^T & 1 |
|
\end{bmatrix} \in \mathbb{R}^{3 \times 3} ~\middle|~ \mathbf{C} \in SO(2), \mathbf{r} \in \mathbb{R}^2 \right\} \\ |
|
\mathfrak{se}(2) &= \left\{ \boldsymbol{\Xi} = |
|
\boldsymbol{\xi}^\wedge \in \mathbb{R}^{3 \times 3} ~\middle|~ |
|
\boldsymbol{\xi}= |
|
\begin{bmatrix} |
|
\boldsymbol{\rho} \\ \phi |
|
\end{bmatrix} \in \mathbb{R}^3, \boldsymbol{\rho} \in \mathbb{R}^2, \phi \in \mathbb{R} \right\}\end{split}\]</div> |
|
<dl class="field-list simple"> |
|
<dt class="field-odd">Variables</dt> |
|
<dd class="field-odd"><ul class="simple"> |
|
<li><p><strong>dim</strong> – Dimension of the rotation matrix.</p></li> |
|
<li><p><strong>dof</strong> – Underlying degrees of freedom (i.e., dimension of the tangent space).</p></li> |
|
<li><p><strong>rot</strong> – Storage for the rotation matrix <span class="math notranslate nohighlight">\(\mathbf{C}\)</span>.</p></li> |
|
<li><p><strong>trans</strong> – Storage for the translation vector <span class="math notranslate nohighlight">\(\mathbf{r}\)</span>.</p></li> |
|
</ul> |
|
</dd> |
|
</dl> |
|
<dl class="attribute"> |
|
<dt id="liegroups.numpy.se2.SE2Matrix.RotationType"> |
|
<code class="sig-name descname">RotationType</code><a class="headerlink" href="#liegroups.numpy.se2.SE2Matrix.RotationType" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>alias of <a class="reference internal" href="#liegroups.numpy.so2.SO2Matrix" title="liegroups.numpy.so2.SO2Matrix"><code class="xref py py-class docutils literal notranslate"><span class="pre">liegroups.numpy.so2.SO2Matrix</span></code></a></p> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.se2.SE2Matrix.adjoint"> |
|
<code class="sig-name descname">adjoint</code><span class="sig-paren">(</span><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.se2.SE2Matrix.adjoint" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Adjoint matrix of the transformation.</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\begin{split}\text{Ad}(\mathbf{T}) = |
|
\begin{bmatrix} |
|
\mathbf{C} & 1^\wedge \mathbf{r} \\ |
|
\mathbf{0}^T & 1 |
|
\end{bmatrix} |
|
\in \mathbb{R}^{3 \times 3}\end{split}\]</div> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.se2.SE2Matrix.as_matrix"> |
|
<code class="sig-name descname">as_matrix</code><span class="sig-paren">(</span><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.se2.SE2Matrix.as_matrix" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Return the matrix representation of the rotation.</p> |
|
</dd></dl> |
|
|
|
<dl class="attribute"> |
|
<dt id="liegroups.numpy.se2.SE2Matrix.dim"> |
|
<code class="sig-name descname">dim</code><em class="property"> = 3</em><a class="headerlink" href="#liegroups.numpy.se2.SE2Matrix.dim" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Dimension of the transformation matrix.</p> |
|
</dd></dl> |
|
|
|
<dl class="attribute"> |
|
<dt id="liegroups.numpy.se2.SE2Matrix.dof"> |
|
<code class="sig-name descname">dof</code><em class="property"> = 3</em><a class="headerlink" href="#liegroups.numpy.se2.SE2Matrix.dof" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Underlying degrees of freedom (i.e., dimension of the tangent space).</p> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.se2.SE2Matrix.dot"> |
|
<code class="sig-name descname">dot</code><span class="sig-paren">(</span><em class="sig-param">other</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.se2.SE2Matrix.dot" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Multiply another rotation or one or more vectors on the left.</p> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.se2.SE2Matrix.exp"> |
|
<em class="property">classmethod </em><code class="sig-name descname">exp</code><span class="sig-paren">(</span><em class="sig-param">xi</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.se2.SE2Matrix.exp" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Exponential map for <span class="math notranslate nohighlight">\(SE(2)\)</span>, which computes a transformation from a tangent vector:</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\begin{split}\mathbf{T}(\boldsymbol{\xi}) = |
|
\exp(\boldsymbol{\xi}^\wedge) = |
|
\begin{bmatrix} |
|
\exp(\phi ^\wedge) & \mathbf{J} \boldsymbol{\rho} \\ |
|
\mathbf{0} ^ T & 1 |
|
\end{bmatrix}\end{split}\]</div> |
|
<p>This is the inverse operation to <code class="xref py py-meth docutils literal notranslate"><span class="pre">log()</span></code>.</p> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.se2.SE2Matrix.from_matrix"> |
|
<em class="property">classmethod </em><code class="sig-name descname">from_matrix</code><span class="sig-paren">(</span><em class="sig-param">mat</em>, <em class="sig-param">normalize=False</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.se2.SE2Matrix.from_matrix" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Create a transformation from a matrix (safe, but slower).</p> |
|
<p>Throws an error if mat is invalid and normalize=False. |
|
If normalize=True invalid matrices will be normalized to be valid.</p> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.se2.SE2Matrix.identity"> |
|
<em class="property">classmethod </em><code class="sig-name descname">identity</code><span class="sig-paren">(</span><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.se2.SE2Matrix.identity" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Return the identity transformation.</p> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.se2.SE2Matrix.inv"> |
|
<code class="sig-name descname">inv</code><span class="sig-paren">(</span><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.se2.SE2Matrix.inv" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Return the inverse transformation:</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\begin{split}\mathbf{T}^{-1} = |
|
\begin{bmatrix} |
|
\mathbf{C}^T & -\mathbf{C}^T\mathbf{r} \\ |
|
\mathbf{0}^T & 1 |
|
\end{bmatrix}\end{split}\]</div> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.se2.SE2Matrix.inv_left_jacobian"> |
|
<em class="property">classmethod </em><code class="sig-name descname">inv_left_jacobian</code><span class="sig-paren">(</span><em class="sig-param">xi</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.se2.SE2Matrix.inv_left_jacobian" title="Permalink to this definition">¶</a></dt> |
|
<dd><p><span class="math notranslate nohighlight">\(SE(2)\)</span> inverse left Jacobian.</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\mathcal{J}^{-1}(\boldsymbol{\xi})\]</div> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.se2.SE2Matrix.is_valid_matrix"> |
|
<em class="property">classmethod </em><code class="sig-name descname">is_valid_matrix</code><span class="sig-paren">(</span><em class="sig-param">mat</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.se2.SE2Matrix.is_valid_matrix" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Check if a matrix is a valid transformation matrix.</p> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.se2.SE2Matrix.left_jacobian"> |
|
<em class="property">classmethod </em><code class="sig-name descname">left_jacobian</code><span class="sig-paren">(</span><em class="sig-param">xi</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.se2.SE2Matrix.left_jacobian" title="Permalink to this definition">¶</a></dt> |
|
<dd><p><span class="math notranslate nohighlight">\(SE(2)\)</span> left Jacobian.</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\mathcal{J}(\boldsymbol{\xi})\]</div> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.se2.SE2Matrix.log"> |
|
<code class="sig-name descname">log</code><span class="sig-paren">(</span><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.se2.SE2Matrix.log" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Logarithmic map for <span class="math notranslate nohighlight">\(SE(2)\)</span>, which computes a tangent vector from a transformation:</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\begin{split}\boldsymbol{\xi}(\mathbf{T}) = |
|
\ln(\mathbf{T})^\vee = |
|
\begin{bmatrix} |
|
\mathbf{J} ^ {-1} \mathbf{r} \\ |
|
\ln(\boldsymbol{C}) ^\vee |
|
\end{bmatrix}\end{split}\]</div> |
|
<p>This is the inverse operation to <code class="xref py py-meth docutils literal notranslate"><span class="pre">log()</span></code>.</p> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.se2.SE2Matrix.normalize"> |
|
<code class="sig-name descname">normalize</code><span class="sig-paren">(</span><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.se2.SE2Matrix.normalize" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Normalize the transformation matrix to ensure it is valid and |
|
negate the effect of rounding errors.</p> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.se2.SE2Matrix.odot"> |
|
<em class="property">classmethod </em><code class="sig-name descname">odot</code><span class="sig-paren">(</span><em class="sig-param">p</em>, <em class="sig-param">directional=False</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.se2.SE2Matrix.odot" title="Permalink to this definition">¶</a></dt> |
|
<dd><p><span class="math notranslate nohighlight">\(SE(2)\)</span> odot operator as defined by Barfoot.</p> |
|
<p>This is the Jacobian of a vector</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\begin{split}\mathbf{p} = |
|
\begin{bmatrix} |
|
sx \\ sy \\ sz \\ s |
|
\end{bmatrix} = |
|
\begin{bmatrix} |
|
\boldsymbol{\epsilon} \\ \eta |
|
\end{bmatrix}\end{split}\]</div> |
|
<p>with respect to a perturbation in the underlying parameters of <span class="math notranslate nohighlight">\(\mathbf{T}\)</span>.</p> |
|
<p>If <span class="math notranslate nohighlight">\(\mathbf{p}\)</span> is given in Euclidean coordinates and directional=False, the missing scale value <span class="math notranslate nohighlight">\(\eta\)</span> is assumed to be 1 and the Jacobian is 2x3. If directional=True, <span class="math notranslate nohighlight">\(\eta\)</span> is assumed to be 0:</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\mathbf{p}^\odot = |
|
\begin{bmatrix} |
|
\eta \mathbf{1} & 1^\wedge \boldsymbol{\epsilon} |
|
\end{bmatrix}\]</div> |
|
<p>If <span class="math notranslate nohighlight">\(\mathbf{p}\)</span> is given in Homogeneous coordinates, the Jacobian is 3x3:</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\begin{split}\mathbf{p}^\odot = |
|
\begin{bmatrix} |
|
\eta \mathbf{1} & 1^\wedge \boldsymbol{\epsilon} \\ |
|
\mathbf{0}^T & 0 |
|
\end{bmatrix}\end{split}\]</div> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.se2.SE2Matrix.perturb"> |
|
<code class="sig-name descname">perturb</code><span class="sig-paren">(</span><em class="sig-param">xi</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.se2.SE2Matrix.perturb" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Perturb the transformation in-place on the left by a vector in its local tangent space.</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\mathbf{T} \gets \exp(\boldsymbol{\xi}^\wedge) \mathbf{T}\]</div> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.se2.SE2Matrix.vee"> |
|
<em class="property">classmethod </em><code class="sig-name descname">vee</code><span class="sig-paren">(</span><em class="sig-param">Xi</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.se2.SE2Matrix.vee" title="Permalink to this definition">¶</a></dt> |
|
<dd><p><span class="math notranslate nohighlight">\(SE(2)\)</span> vee operator as defined by Barfoot.</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\boldsymbol{\xi} = \boldsymbol{\Xi} ^\vee\]</div> |
|
<p>This is the inverse operation to <code class="xref py py-meth docutils literal notranslate"><span class="pre">wedge()</span></code>.</p> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.se2.SE2Matrix.wedge"> |
|
<em class="property">classmethod </em><code class="sig-name descname">wedge</code><span class="sig-paren">(</span><em class="sig-param">xi</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.se2.SE2Matrix.wedge" title="Permalink to this definition">¶</a></dt> |
|
<dd><p><span class="math notranslate nohighlight">\(SE(2)\)</span> wedge operator as defined by Barfoot.</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\begin{split}\boldsymbol{\Xi} = |
|
\boldsymbol{\xi} ^\wedge = |
|
\begin{bmatrix} |
|
\phi ^\wedge & \boldsymbol{\rho} \\ |
|
\mathbf{0} ^ T & 0 |
|
\end{bmatrix}\end{split}\]</div> |
|
<p>This is the inverse operation to <code class="xref py py-meth docutils literal notranslate"><span class="pre">vee()</span></code>.</p> |
|
</dd></dl> |
|
|
|
</dd></dl> |
|
|
|
</div> |
|
<div class="section" id="so-3"> |
|
<h2>SO(3)<a class="headerlink" href="#so-3" title="Permalink to this headline">¶</a></h2> |
|
<dl class="attribute"> |
|
<dt id="liegroups.SO3"> |
|
<code class="sig-prename descclassname">liegroups.</code><code class="sig-name descname">SO3</code><a class="headerlink" href="#liegroups.SO3" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>alias of <a class="reference internal" href="#liegroups.numpy.so3.SO3Matrix" title="liegroups.numpy.so3.SO3Matrix"><code class="xref py py-class docutils literal notranslate"><span class="pre">liegroups.numpy.so3.SO3Matrix</span></code></a></p> |
|
</dd></dl> |
|
|
|
<dl class="class"> |
|
<dt id="liegroups.numpy.so3.SO3Matrix"> |
|
<em class="property">class </em><code class="sig-prename descclassname">liegroups.numpy.so3.</code><code class="sig-name descname">SO3Matrix</code><span class="sig-paren">(</span><em class="sig-param">mat</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.so3.SO3Matrix" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Rotation matrix in <span class="math notranslate nohighlight">\(SO(3)\)</span> using active (alibi) transformations.</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\begin{split}SO(3) &= \left\{ \mathbf{C} \in \mathbb{R}^{3 \times 3} ~\middle|~ \mathbf{C}\mathbf{C}^T = \mathbf{1}, \det \mathbf{C} = 1 \right\} \\ |
|
\mathfrak{so}(3) &= \left\{ \boldsymbol{\Phi} = \boldsymbol{\phi}^\wedge \in \mathbb{R}^{3 \times 3} ~\middle|~ \boldsymbol{\phi} = \phi \mathbf{a} \in \mathbb{R}^3, \phi = \Vert \boldsymbol{\phi} \Vert \right\}\end{split}\]</div> |
|
<dl class="field-list simple"> |
|
<dt class="field-odd">Variables</dt> |
|
<dd class="field-odd"><ul class="simple"> |
|
<li><p><strong>dim</strong> – Dimension of the rotation matrix.</p></li> |
|
<li><p><strong>dof</strong> – Underlying degrees of freedom (i.e., dimension of the tangent space).</p></li> |
|
<li><p><strong>mat</strong> – Storage for the rotation matrix <span class="math notranslate nohighlight">\(\mathbf{C}\)</span>.</p></li> |
|
</ul> |
|
</dd> |
|
</dl> |
|
<dl class="method"> |
|
<dt id="liegroups.numpy.so3.SO3Matrix.adjoint"> |
|
<code class="sig-name descname">adjoint</code><span class="sig-paren">(</span><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.so3.SO3Matrix.adjoint" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Adjoint matrix of the transformation.</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\text{Ad}(\mathbf{C}) = \mathbf{C} |
|
\in \mathbb{R}^{3 \times 3}\]</div> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.so3.SO3Matrix.as_matrix"> |
|
<code class="sig-name descname">as_matrix</code><span class="sig-paren">(</span><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.so3.SO3Matrix.as_matrix" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Return the matrix representation of the rotation.</p> |
|
</dd></dl> |
|
|
|
<dl class="attribute"> |
|
<dt id="liegroups.numpy.so3.SO3Matrix.dim"> |
|
<code class="sig-name descname">dim</code><em class="property"> = 3</em><a class="headerlink" href="#liegroups.numpy.so3.SO3Matrix.dim" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Dimension of the transformation matrix.</p> |
|
</dd></dl> |
|
|
|
<dl class="attribute"> |
|
<dt id="liegroups.numpy.so3.SO3Matrix.dof"> |
|
<code class="sig-name descname">dof</code><em class="property"> = 3</em><a class="headerlink" href="#liegroups.numpy.so3.SO3Matrix.dof" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Underlying degrees of freedom (i.e., dimension of the tangent space).</p> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.so3.SO3Matrix.dot"> |
|
<code class="sig-name descname">dot</code><span class="sig-paren">(</span><em class="sig-param">other</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.so3.SO3Matrix.dot" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Multiply another rotation or one or more vectors on the left.</p> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.so3.SO3Matrix.exp"> |
|
<em class="property">classmethod </em><code class="sig-name descname">exp</code><span class="sig-paren">(</span><em class="sig-param">phi</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.so3.SO3Matrix.exp" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Exponential map for <span class="math notranslate nohighlight">\(SO(3)\)</span>, which computes a transformation from a tangent vector:</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\begin{split}\mathbf{C}(\boldsymbol{\phi}) = |
|
\exp(\boldsymbol{\phi}^\wedge) = |
|
\begin{cases} |
|
\mathbf{1} + \boldsymbol{\phi}^\wedge, & \text{if } \phi \text{ is small} \\ |
|
\cos \phi \mathbf{1} + |
|
(1 - \cos \phi) \mathbf{a}\mathbf{a}^T + |
|
\sin \phi \mathbf{a}^\wedge, & \text{otherwise} |
|
\end{cases}\end{split}\]</div> |
|
<p>This is the inverse operation to <code class="xref py py-meth docutils literal notranslate"><span class="pre">log()</span></code>.</p> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.so3.SO3Matrix.from_matrix"> |
|
<em class="property">classmethod </em><code class="sig-name descname">from_matrix</code><span class="sig-paren">(</span><em class="sig-param">mat</em>, <em class="sig-param">normalize=False</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.so3.SO3Matrix.from_matrix" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Create a rotation from a matrix (safe, but slower).</p> |
|
<p>Throws an error if mat is invalid and normalize=False. |
|
If normalize=True invalid matrices will be normalized to be valid.</p> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.so3.SO3Matrix.from_quaternion"> |
|
<em class="property">classmethod </em><code class="sig-name descname">from_quaternion</code><span class="sig-paren">(</span><em class="sig-param">quat</em>, <em class="sig-param">ordering='wxyz'</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.so3.SO3Matrix.from_quaternion" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Form a rotation matrix from a unit length quaternion.</p> |
|
<p>Valid orderings are ‘xyzw’ and ‘wxyz’.</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\begin{split}\mathbf{C} = |
|
\begin{bmatrix} |
|
1 - 2 (y^2 + z^2) & 2 (xy - wz) & 2 (wy + xz) \\ |
|
2 (wz + xy) & 1 - 2 (x^2 + z^2) & 2 (yz - wx) \\ |
|
2 (xz - wy) & 2 (wx + yz) & 1 - 2 (x^2 + y^2) |
|
\end{bmatrix}\end{split}\]</div> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.so3.SO3Matrix.from_rpy"> |
|
<em class="property">classmethod </em><code class="sig-name descname">from_rpy</code><span class="sig-paren">(</span><em class="sig-param">roll</em>, <em class="sig-param">pitch</em>, <em class="sig-param">yaw</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.so3.SO3Matrix.from_rpy" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Form a rotation matrix from RPY Euler angles <span class="math notranslate nohighlight">\((\alpha, \beta, \gamma)\)</span>.</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\mathbf{C} = \mathbf{C}_z(\gamma) \mathbf{C}_y(\beta) \mathbf{C}_x(\alpha)\]</div> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.so3.SO3Matrix.identity"> |
|
<em class="property">classmethod </em><code class="sig-name descname">identity</code><span class="sig-paren">(</span><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.so3.SO3Matrix.identity" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Return the identity rotation.</p> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.so3.SO3Matrix.inv"> |
|
<code class="sig-name descname">inv</code><span class="sig-paren">(</span><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.so3.SO3Matrix.inv" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Return the inverse rotation:</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\mathbf{C}^{-1} = \mathbf{C}^T\]</div> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.so3.SO3Matrix.inv_left_jacobian"> |
|
<em class="property">classmethod </em><code class="sig-name descname">inv_left_jacobian</code><span class="sig-paren">(</span><em class="sig-param">phi</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.so3.SO3Matrix.inv_left_jacobian" title="Permalink to this definition">¶</a></dt> |
|
<dd><p><span class="math notranslate nohighlight">\(SO(3)\)</span> inverse left Jacobian.</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\begin{split}\mathbf{J}^{-1}(\boldsymbol{\phi}) = |
|
\begin{cases} |
|
\mathbf{1} - \frac{1}{2} \boldsymbol{\phi}^\wedge, & \text{if } \phi \text{ is small} \\ |
|
\frac{\phi}{2} \cot \frac{\phi}{2} \mathbf{1} + |
|
\left( 1 - \frac{\phi}{2} \cot \frac{\phi}{2} \right) \mathbf{a}\mathbf{a}^T - |
|
\frac{\phi}{2} \mathbf{a}^\wedge, & \text{otherwise} |
|
\end{cases}\end{split}\]</div> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.so3.SO3Matrix.is_valid_matrix"> |
|
<em class="property">classmethod </em><code class="sig-name descname">is_valid_matrix</code><span class="sig-paren">(</span><em class="sig-param">mat</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.so3.SO3Matrix.is_valid_matrix" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Check if a matrix is a valid rotation matrix.</p> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.so3.SO3Matrix.left_jacobian"> |
|
<em class="property">classmethod </em><code class="sig-name descname">left_jacobian</code><span class="sig-paren">(</span><em class="sig-param">phi</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.so3.SO3Matrix.left_jacobian" title="Permalink to this definition">¶</a></dt> |
|
<dd><p><span class="math notranslate nohighlight">\(SO(3)\)</span> left Jacobian.</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\begin{split}\mathbf{J}(\boldsymbol{\phi}) = |
|
\begin{cases} |
|
\mathbf{1} + \frac{1}{2} \boldsymbol{\phi}^\wedge, & \text{if } \phi \text{ is small} \\ |
|
\frac{\sin \phi}{\phi} \mathbf{1} + |
|
\left(1 - \frac{\sin \phi}{\phi} \right) \mathbf{a}\mathbf{a}^T + |
|
\frac{1 - \cos \phi}{\phi} \mathbf{a}^\wedge, & \text{otherwise} |
|
\end{cases}\end{split}\]</div> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.so3.SO3Matrix.log"> |
|
<code class="sig-name descname">log</code><span class="sig-paren">(</span><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.so3.SO3Matrix.log" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Logarithmic map for <span class="math notranslate nohighlight">\(SO(3)\)</span>, which computes a tangent vector from a transformation:</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\begin{split}\phi &= \frac{1}{2} \left( \mathrm{Tr}(\mathbf{C}) - 1 \right) \\ |
|
\boldsymbol{\phi}(\mathbf{C}) &= |
|
\ln(\mathbf{C})^\vee = |
|
\begin{cases} |
|
\mathbf{1} - \boldsymbol{\phi}^\wedge, & \text{if } \phi \text{ is small} \\ |
|
\left( \frac{1}{2} \frac{\phi}{\sin \phi} \left( \mathbf{C} - \mathbf{C}^T \right) \right)^\vee, & \text{otherwise} |
|
\end{cases}\end{split}\]</div> |
|
<p>This is the inverse operation to <code class="xref py py-meth docutils literal notranslate"><span class="pre">log()</span></code>.</p> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.so3.SO3Matrix.normalize"> |
|
<code class="sig-name descname">normalize</code><span class="sig-paren">(</span><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.so3.SO3Matrix.normalize" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Normalize the rotation matrix to ensure it is valid and |
|
negate the effect of rounding errors.</p> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.so3.SO3Matrix.perturb"> |
|
<code class="sig-name descname">perturb</code><span class="sig-paren">(</span><em class="sig-param">phi</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.so3.SO3Matrix.perturb" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Perturb the rotation in-place on the left by a vector in its local tangent space.</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\mathbf{C} \gets \exp(\boldsymbol{\phi}^\wedge) \mathbf{C}\]</div> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.so3.SO3Matrix.rotx"> |
|
<em class="property">classmethod </em><code class="sig-name descname">rotx</code><span class="sig-paren">(</span><em class="sig-param">angle_in_radians</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.so3.SO3Matrix.rotx" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Form a rotation matrix given an angle in rad about the x-axis.</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\begin{split}\mathbf{C}_x(\phi) = |
|
\begin{bmatrix} |
|
1 & 0 & 0 \\ |
|
0 & \cos \phi & -\sin \phi \\ |
|
0 & \sin \phi & \cos \phi |
|
\end{bmatrix}\end{split}\]</div> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.so3.SO3Matrix.roty"> |
|
<em class="property">classmethod </em><code class="sig-name descname">roty</code><span class="sig-paren">(</span><em class="sig-param">angle_in_radians</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.so3.SO3Matrix.roty" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Form a rotation matrix given an angle in rad about the y-axis.</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\begin{split}\mathbf{C}_y(\phi) = |
|
\begin{bmatrix} |
|
\cos \phi & 0 & \sin \phi \\ |
|
0 & 1 & 0 \\ |
|
\sin \phi & 0 & \cos \phi |
|
\end{bmatrix}\end{split}\]</div> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.so3.SO3Matrix.rotz"> |
|
<em class="property">classmethod </em><code class="sig-name descname">rotz</code><span class="sig-paren">(</span><em class="sig-param">angle_in_radians</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.so3.SO3Matrix.rotz" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Form a rotation matrix given an angle in rad about the z-axis.</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\begin{split}\mathbf{C}_z(\phi) = |
|
\begin{bmatrix} |
|
\cos \phi & -\sin \phi & 0 \\ |
|
\sin \phi & \cos \phi & 0 \\ |
|
0 & 0 & 1 |
|
\end{bmatrix}\end{split}\]</div> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.so3.SO3Matrix.to_quaternion"> |
|
<code class="sig-name descname">to_quaternion</code><span class="sig-paren">(</span><em class="sig-param">ordering='wxyz'</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.so3.SO3Matrix.to_quaternion" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Convert a rotation matrix to a unit length quaternion.</p> |
|
<p>Valid orderings are ‘xyzw’ and ‘wxyz’.</p> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.so3.SO3Matrix.to_rpy"> |
|
<code class="sig-name descname">to_rpy</code><span class="sig-paren">(</span><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.so3.SO3Matrix.to_rpy" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Convert a rotation matrix to RPY Euler angles <span class="math notranslate nohighlight">\((\alpha, \beta, \gamma)\)</span>.</p> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.so3.SO3Matrix.vee"> |
|
<em class="property">classmethod </em><code class="sig-name descname">vee</code><span class="sig-paren">(</span><em class="sig-param">Phi</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.so3.SO3Matrix.vee" title="Permalink to this definition">¶</a></dt> |
|
<dd><p><span class="math notranslate nohighlight">\(SO(3)\)</span> vee operator as defined by Barfoot.</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\phi = \boldsymbol{\Phi}^\vee\]</div> |
|
<p>This is the inverse operation to <code class="xref py py-meth docutils literal notranslate"><span class="pre">wedge()</span></code>.</p> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.so3.SO3Matrix.wedge"> |
|
<em class="property">classmethod </em><code class="sig-name descname">wedge</code><span class="sig-paren">(</span><em class="sig-param">phi</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.so3.SO3Matrix.wedge" title="Permalink to this definition">¶</a></dt> |
|
<dd><p><span class="math notranslate nohighlight">\(SO(3)\)</span> wedge operator as defined by Barfoot.</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\begin{split}\boldsymbol{\Phi} = |
|
\boldsymbol{\phi}^\wedge = |
|
\begin{bmatrix} |
|
0 & -\phi_3 & \phi_2 \\ |
|
\phi_3 & 0 & -\phi_1 \\ |
|
-\phi_2 & \phi_1 & 0 |
|
\end{bmatrix}\end{split}\]</div> |
|
<p>This is the inverse operation to <code class="xref py py-meth docutils literal notranslate"><span class="pre">vee()</span></code>.</p> |
|
</dd></dl> |
|
|
|
</dd></dl> |
|
|
|
</div> |
|
<div class="section" id="se-3"> |
|
<h2>SE(3)<a class="headerlink" href="#se-3" title="Permalink to this headline">¶</a></h2> |
|
<dl class="attribute"> |
|
<dt id="liegroups.SE3"> |
|
<code class="sig-prename descclassname">liegroups.</code><code class="sig-name descname">SE3</code><a class="headerlink" href="#liegroups.SE3" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>alias of <a class="reference internal" href="#liegroups.numpy.se3.SE3Matrix" title="liegroups.numpy.se3.SE3Matrix"><code class="xref py py-class docutils literal notranslate"><span class="pre">liegroups.numpy.se3.SE3Matrix</span></code></a></p> |
|
</dd></dl> |
|
|
|
<dl class="class"> |
|
<dt id="liegroups.numpy.se3.SE3Matrix"> |
|
<em class="property">class </em><code class="sig-prename descclassname">liegroups.numpy.se3.</code><code class="sig-name descname">SE3Matrix</code><span class="sig-paren">(</span><em class="sig-param">rot</em>, <em class="sig-param">trans</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.se3.SE3Matrix" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Homogeneous transformation matrix in <span class="math notranslate nohighlight">\(SE(3)\)</span> using active (alibi) transformations.</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\begin{split}SE(3) &= \left\{ \mathbf{T}= |
|
\begin{bmatrix} |
|
\mathbf{C} & \mathbf{r} \\ |
|
\mathbf{0}^T & 1 |
|
\end{bmatrix} \in \mathbb{R}^{4 \times 4} ~\middle|~ \mathbf{C} \in SO(3), \mathbf{r} \in \mathbb{R}^3 \right\} \\ |
|
\mathfrak{se}(3) &= \left\{ \boldsymbol{\Xi} = |
|
\boldsymbol{\xi}^\wedge \in \mathbb{R}^{4 \times 4} ~\middle|~ |
|
\boldsymbol{\xi}= |
|
\begin{bmatrix} |
|
\boldsymbol{\rho} \\ \boldsymbol{\phi} |
|
\end{bmatrix} \in \mathbb{R}^6, \boldsymbol{\rho} \in \mathbb{R}^3, \boldsymbol{\phi} \in \mathbb{R}^3 \right\}\end{split}\]</div> |
|
<dl class="field-list simple"> |
|
<dt class="field-odd">Variables</dt> |
|
<dd class="field-odd"><ul class="simple"> |
|
<li><p><strong>dim</strong> – Dimension of the rotation matrix.</p></li> |
|
<li><p><strong>dof</strong> – Underlying degrees of freedom (i.e., dimension of the tangent space).</p></li> |
|
<li><p><strong>rot</strong> – Storage for the rotation matrix <span class="math notranslate nohighlight">\(\mathbf{C}\)</span>.</p></li> |
|
<li><p><strong>trans</strong> – Storage for the translation vector <span class="math notranslate nohighlight">\(\mathbf{r}\)</span>.</p></li> |
|
</ul> |
|
</dd> |
|
</dl> |
|
<dl class="attribute"> |
|
<dt id="liegroups.numpy.se3.SE3Matrix.RotationType"> |
|
<code class="sig-name descname">RotationType</code><a class="headerlink" href="#liegroups.numpy.se3.SE3Matrix.RotationType" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>alias of <a class="reference internal" href="#liegroups.numpy.so3.SO3Matrix" title="liegroups.numpy.so3.SO3Matrix"><code class="xref py py-class docutils literal notranslate"><span class="pre">liegroups.numpy.so3.SO3Matrix</span></code></a></p> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.se3.SE3Matrix.adjoint"> |
|
<code class="sig-name descname">adjoint</code><span class="sig-paren">(</span><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.se3.SE3Matrix.adjoint" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Adjoint matrix of the transformation.</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\begin{split}\text{Ad}(\mathbf{T}) = |
|
\begin{bmatrix} |
|
\mathbf{C} & \mathbf{r}^\wedge\mathbf{C} \\ |
|
\mathbf{0} & \mathbf{C} |
|
\end{bmatrix} |
|
\in \mathbb{R}^{6 \times 6}\end{split}\]</div> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.se3.SE3Matrix.as_matrix"> |
|
<code class="sig-name descname">as_matrix</code><span class="sig-paren">(</span><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.se3.SE3Matrix.as_matrix" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Return the matrix representation of the rotation.</p> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.se3.SE3Matrix.curlyvee"> |
|
<em class="property">classmethod </em><code class="sig-name descname">curlyvee</code><span class="sig-paren">(</span><em class="sig-param">Psi</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.se3.SE3Matrix.curlyvee" title="Permalink to this definition">¶</a></dt> |
|
<dd><p><span class="math notranslate nohighlight">\(SE(3)\)</span> curlyvee operator as defined by Barfoot.</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\boldsymbol{\xi} = |
|
\boldsymbol{\Psi}^\curlyvee\]</div> |
|
<p>This is the inverse operation to <code class="xref py py-meth docutils literal notranslate"><span class="pre">curlywedge()</span></code>.</p> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.se3.SE3Matrix.curlywedge"> |
|
<em class="property">classmethod </em><code class="sig-name descname">curlywedge</code><span class="sig-paren">(</span><em class="sig-param">xi</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.se3.SE3Matrix.curlywedge" title="Permalink to this definition">¶</a></dt> |
|
<dd><p><span class="math notranslate nohighlight">\(SE(3)\)</span> curlywedge operator as defined by Barfoot.</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\begin{split}\boldsymbol{\Psi} = |
|
\boldsymbol{\xi}^\curlywedge = |
|
\begin{bmatrix} |
|
\boldsymbol{\phi}^\wedge & \boldsymbol{\rho}^\wedge \\ |
|
\mathbf{0} & \boldsymbol{\phi}^\wedge |
|
\end{bmatrix}\end{split}\]</div> |
|
<p>This is the inverse operation to <code class="xref py py-meth docutils literal notranslate"><span class="pre">curlyvee()</span></code>.</p> |
|
</dd></dl> |
|
|
|
<dl class="attribute"> |
|
<dt id="liegroups.numpy.se3.SE3Matrix.dim"> |
|
<code class="sig-name descname">dim</code><em class="property"> = 4</em><a class="headerlink" href="#liegroups.numpy.se3.SE3Matrix.dim" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Dimension of the transformation matrix.</p> |
|
</dd></dl> |
|
|
|
<dl class="attribute"> |
|
<dt id="liegroups.numpy.se3.SE3Matrix.dof"> |
|
<code class="sig-name descname">dof</code><em class="property"> = 6</em><a class="headerlink" href="#liegroups.numpy.se3.SE3Matrix.dof" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Underlying degrees of freedom (i.e., dimension of the tangent space).</p> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.se3.SE3Matrix.dot"> |
|
<code class="sig-name descname">dot</code><span class="sig-paren">(</span><em class="sig-param">other</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.se3.SE3Matrix.dot" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Multiply another rotation or one or more vectors on the left.</p> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.se3.SE3Matrix.exp"> |
|
<em class="property">classmethod </em><code class="sig-name descname">exp</code><span class="sig-paren">(</span><em class="sig-param">xi</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.se3.SE3Matrix.exp" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Exponential map for <span class="math notranslate nohighlight">\(SE(3)\)</span>, which computes a transformation from a tangent vector:</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\begin{split}\mathbf{T}(\boldsymbol{\xi}) = |
|
\exp(\boldsymbol{\xi}^\wedge) = |
|
\begin{bmatrix} |
|
\exp(\boldsymbol{\phi}^\wedge) & \mathbf{J} \boldsymbol{\rho} \\ |
|
\mathbf{0} ^ T & 1 |
|
\end{bmatrix}\end{split}\]</div> |
|
<p>This is the inverse operation to <code class="xref py py-meth docutils literal notranslate"><span class="pre">log()</span></code>.</p> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.se3.SE3Matrix.from_matrix"> |
|
<em class="property">classmethod </em><code class="sig-name descname">from_matrix</code><span class="sig-paren">(</span><em class="sig-param">mat</em>, <em class="sig-param">normalize=False</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.se3.SE3Matrix.from_matrix" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Create a transformation from a matrix (safe, but slower).</p> |
|
<p>Throws an error if mat is invalid and normalize=False. |
|
If normalize=True invalid matrices will be normalized to be valid.</p> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.se3.SE3Matrix.identity"> |
|
<em class="property">classmethod </em><code class="sig-name descname">identity</code><span class="sig-paren">(</span><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.se3.SE3Matrix.identity" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Return the identity transformation.</p> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.se3.SE3Matrix.inv"> |
|
<code class="sig-name descname">inv</code><span class="sig-paren">(</span><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.se3.SE3Matrix.inv" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Return the inverse transformation:</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\begin{split}\mathbf{T}^{-1} = |
|
\begin{bmatrix} |
|
\mathbf{C}^T & -\mathbf{C}^T\mathbf{r} \\ |
|
\mathbf{0}^T & 1 |
|
\end{bmatrix}\end{split}\]</div> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.se3.SE3Matrix.inv_left_jacobian"> |
|
<em class="property">classmethod </em><code class="sig-name descname">inv_left_jacobian</code><span class="sig-paren">(</span><em class="sig-param">xi</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.se3.SE3Matrix.inv_left_jacobian" title="Permalink to this definition">¶</a></dt> |
|
<dd><p><span class="math notranslate nohighlight">\(SE(3)\)</span> inverse left Jacobian.</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\begin{split}\mathcal{J}^{-1}(\boldsymbol{\xi}) = |
|
\begin{bmatrix} |
|
\mathbf{J}^{-1} & -\mathbf{J}^{-1} \mathbf{Q} \mathbf{J}^{-1} \\ |
|
\mathbf{0} & \mathbf{J}^{-1} |
|
\end{bmatrix}\end{split}\]</div> |
|
<p>with <span class="math notranslate nohighlight">\(\mathbf{J}^{-1}\)</span> as in <code class="xref py py-meth docutils literal notranslate"><span class="pre">liegroups.SO3.inv_left_jacobian()</span></code> and <span class="math notranslate nohighlight">\(\mathbf{Q}\)</span> as in <code class="xref py py-meth docutils literal notranslate"><span class="pre">left_jacobian_Q_matrix()</span></code>.</p> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.se3.SE3Matrix.is_valid_matrix"> |
|
<em class="property">classmethod </em><code class="sig-name descname">is_valid_matrix</code><span class="sig-paren">(</span><em class="sig-param">mat</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.se3.SE3Matrix.is_valid_matrix" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Check if a matrix is a valid transformation matrix.</p> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.se3.SE3Matrix.left_jacobian"> |
|
<em class="property">classmethod </em><code class="sig-name descname">left_jacobian</code><span class="sig-paren">(</span><em class="sig-param">xi</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.se3.SE3Matrix.left_jacobian" title="Permalink to this definition">¶</a></dt> |
|
<dd><p><span class="math notranslate nohighlight">\(SE(3)\)</span> left Jacobian.</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\begin{split}\mathcal{J}(\boldsymbol{\xi}) = |
|
\begin{bmatrix} |
|
\mathbf{J} & \mathbf{Q} \\ |
|
\mathbf{0} & \mathbf{J} |
|
\end{bmatrix}\end{split}\]</div> |
|
<p>with <span class="math notranslate nohighlight">\(\mathbf{J}\)</span> as in <code class="xref py py-meth docutils literal notranslate"><span class="pre">liegroups.SO3.left_jacobian()</span></code> and <span class="math notranslate nohighlight">\(\mathbf{Q}\)</span> as in <code class="xref py py-meth docutils literal notranslate"><span class="pre">left_jacobian_Q_matrix()</span></code>.</p> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.se3.SE3Matrix.left_jacobian_Q_matrix"> |
|
<em class="property">classmethod </em><code class="sig-name descname">left_jacobian_Q_matrix</code><span class="sig-paren">(</span><em class="sig-param">xi</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.se3.SE3Matrix.left_jacobian_Q_matrix" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>The <span class="math notranslate nohighlight">\(\mathbf{Q}\)</span> matrix used to compute <span class="math notranslate nohighlight">\(\mathcal{J}\)</span> in <code class="xref py py-meth docutils literal notranslate"><span class="pre">left_jacobian()</span></code> and <span class="math notranslate nohighlight">\(\mathcal{J}^{-1}\)</span> in <code class="xref py py-meth docutils literal notranslate"><span class="pre">inv_left_jacobian()</span></code>.</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\begin{split}\mathbf{Q}(\boldsymbol{\xi}) = |
|
\frac{1}{2}\boldsymbol{\rho}^\wedge &+ |
|
\left( \frac{\phi - \sin \phi}{\phi^3} \right) |
|
\left( |
|
\boldsymbol{\phi}^\wedge \boldsymbol{\rho}^\wedge + |
|
\boldsymbol{\rho}^\wedge \boldsymbol{\phi}^\wedge + |
|
\boldsymbol{\phi}^\wedge \boldsymbol{\rho}^\wedge \boldsymbol{\phi}^\wedge |
|
\right) \\ &+ |
|
\left( \frac{\phi^2 + 2 \cos \phi - 2}{2 \phi^4} \right) |
|
\left( |
|
\boldsymbol{\phi}^\wedge \boldsymbol{\phi}^\wedge \boldsymbol{\rho}^\wedge + |
|
\boldsymbol{\rho}^\wedge \boldsymbol{\phi}^\wedge \boldsymbol{\phi}^\wedge - |
|
3 \boldsymbol{\phi}^\wedge \boldsymbol{\rho}^\wedge \boldsymbol{\phi}^\wedge |
|
\right) \\ &+ |
|
\left( \frac{2 \phi - 3 \sin \phi + \phi \cos \phi}{2 \phi^5} \right) |
|
\left( |
|
\boldsymbol{\phi}^\wedge \boldsymbol{\rho}^\wedge \boldsymbol{\phi}^\wedge \boldsymbol{\phi}^\wedge + |
|
\boldsymbol{\phi}^\wedge \boldsymbol{\phi}^\wedge \boldsymbol{\rho}^\wedge \boldsymbol{\phi}^\wedge |
|
\right)\end{split}\]</div> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.se3.SE3Matrix.log"> |
|
<code class="sig-name descname">log</code><span class="sig-paren">(</span><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.se3.SE3Matrix.log" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Logarithmic map for <span class="math notranslate nohighlight">\(SE(3)\)</span>, which computes a tangent vector from a transformation:</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\begin{split}\boldsymbol{\xi}(\mathbf{T}) = |
|
\ln(\mathbf{T})^\vee = |
|
\begin{bmatrix} |
|
\mathbf{J} ^ {-1} \mathbf{r} \\ |
|
\ln(\boldsymbol{C}) ^\vee |
|
\end{bmatrix}\end{split}\]</div> |
|
<p>This is the inverse operation to <code class="xref py py-meth docutils literal notranslate"><span class="pre">exp()</span></code>.</p> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.se3.SE3Matrix.normalize"> |
|
<code class="sig-name descname">normalize</code><span class="sig-paren">(</span><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.se3.SE3Matrix.normalize" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Normalize the transformation matrix to ensure it is valid and |
|
negate the effect of rounding errors.</p> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.se3.SE3Matrix.odot"> |
|
<em class="property">classmethod </em><code class="sig-name descname">odot</code><span class="sig-paren">(</span><em class="sig-param">p</em>, <em class="sig-param">directional=False</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.se3.SE3Matrix.odot" title="Permalink to this definition">¶</a></dt> |
|
<dd><p><span class="math notranslate nohighlight">\(SE(3)\)</span> odot operator as defined by Barfoot.</p> |
|
<p>This is the Jacobian of a vector</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\begin{split}\mathbf{p} = |
|
\begin{bmatrix} |
|
sx \\ sy \\ sz \\ s |
|
\end{bmatrix} = |
|
\begin{bmatrix} |
|
\boldsymbol{\epsilon} \\ \eta |
|
\end{bmatrix}\end{split}\]</div> |
|
<p>with respect to a perturbation in the underlying parameters of <span class="math notranslate nohighlight">\(\mathbf{T}\)</span>.</p> |
|
<p>If <span class="math notranslate nohighlight">\(\mathbf{p}\)</span> is given in Euclidean coordinates and directional=False, the missing scale value <span class="math notranslate nohighlight">\(\eta\)</span> is assumed to be 1 and the Jacobian is 3x6. If directional=True, <span class="math notranslate nohighlight">\(\eta\)</span> is assumed to be 0:</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\mathbf{p}^\odot = |
|
\begin{bmatrix} |
|
\eta \mathbf{1} & -\boldsymbol{\epsilon}^\wedge |
|
\end{bmatrix}\]</div> |
|
<p>If <span class="math notranslate nohighlight">\(\mathbf{p}\)</span> is given in Homogeneous coordinates, the Jacobian is 4x6:</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\begin{split}\mathbf{p}^\odot = |
|
\begin{bmatrix} |
|
\eta \mathbf{1} & -\boldsymbol{\epsilon}^\wedge \\ |
|
\mathbf{0}^T & \mathbf{0}^T |
|
\end{bmatrix}\end{split}\]</div> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.se3.SE3Matrix.perturb"> |
|
<code class="sig-name descname">perturb</code><span class="sig-paren">(</span><em class="sig-param">xi</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.se3.SE3Matrix.perturb" title="Permalink to this definition">¶</a></dt> |
|
<dd><p>Perturb the transformation in-place on the left by a vector in its local tangent space.</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\mathbf{T} \gets \exp(\boldsymbol{\xi}^\wedge) \mathbf{T}\]</div> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.se3.SE3Matrix.vee"> |
|
<em class="property">classmethod </em><code class="sig-name descname">vee</code><span class="sig-paren">(</span><em class="sig-param">Xi</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.se3.SE3Matrix.vee" title="Permalink to this definition">¶</a></dt> |
|
<dd><p><span class="math notranslate nohighlight">\(SE(3)\)</span> vee operator as defined by Barfoot.</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\boldsymbol{\xi} = \boldsymbol{\Xi} ^\vee\]</div> |
|
<p>This is the inverse operation to <code class="xref py py-meth docutils literal notranslate"><span class="pre">wedge()</span></code>.</p> |
|
</dd></dl> |
|
|
|
<dl class="method"> |
|
<dt id="liegroups.numpy.se3.SE3Matrix.wedge"> |
|
<em class="property">classmethod </em><code class="sig-name descname">wedge</code><span class="sig-paren">(</span><em class="sig-param">xi</em><span class="sig-paren">)</span><a class="headerlink" href="#liegroups.numpy.se3.SE3Matrix.wedge" title="Permalink to this definition">¶</a></dt> |
|
<dd><p><span class="math notranslate nohighlight">\(SE(3)\)</span> wedge operator as defined by Barfoot.</p> |
|
<div class="math notranslate nohighlight"> |
|
\[\begin{split}\boldsymbol{\Xi} = |
|
\boldsymbol{\xi} ^\wedge = |
|
\begin{bmatrix} |
|
\boldsymbol{\phi} ^\wedge & \boldsymbol{\rho} \\ |
|
\mathbf{0} ^ T & 0 |
|
\end{bmatrix}\end{split}\]</div> |
|
<p>This is the inverse operation to <code class="xref py py-meth docutils literal notranslate"><span class="pre">vee()</span></code>.</p> |
|
</dd></dl> |
|
|
|
</dd></dl> |
|
|
|
</div> |
|
</div> |
|
|
|
|
|
</div> |
|
|
|
</div> |
|
<footer> |
|
|
|
<div class="rst-footer-buttons" role="navigation" aria-label="footer navigation"> |
|
|
|
<a href="torch.html" class="btn btn-neutral float-right" title="liegroups.torch" accesskey="n" rel="next">Next <span class="fa fa-arrow-circle-right"></span></a> |
|
|
|
|
|
<a href="index.html" class="btn btn-neutral float-left" title="Lie Groups" accesskey="p" rel="prev"><span class="fa fa-arrow-circle-left"></span> Previous</a> |
|
|
|
</div> |
|
|
|
|
|
<hr/> |
|
|
|
<div role="contentinfo"> |
|
<p> |
|
© Copyright 2019, Lee Clement |
|
|
|
</p> |
|
</div> |
|
Built with <a href="http://sphinx-doc.org/">Sphinx</a> using a <a href="https://github.com/rtfd/sphinx_rtd_theme">theme</a> provided by <a href="https://readthedocs.org">Read the Docs</a>. |
|
|
|
</footer> |
|
|
|
</div> |
|
</div> |
|
|
|
</section> |
|
|
|
</div> |
|
|
|
|
|
|
|
<script type="text/javascript"> |
|
jQuery(function () { |
|
SphinxRtdTheme.Navigation.enable(true); |
|
}); |
|
</script> |
|
|
|
|
|
|
|
|
|
|
|
|
|
</body> |
|
</html> |