Public Member Functions | Static Public Member Functions | Public Attributes | List of all members
gtsam.examples.EqF.G Class Reference

Public Member Functions

def __init__ (self, Rot3 A=Rot3.Identity(), np.ndarray a=np.zeros((3, 3)), List[Rot3] B=None)
 
"G" __mul__ (self, "G" other)
 
"G" exp (np.ndarray x)
 
"G" inv (self)
 

Static Public Member Functions

def identity (int n)
 
np.ndarray Rot3LeftJacobian (np.ndarray arr)
 

Public Attributes

 A
 
 a
 
 B
 

Detailed Description

Symmetry group (SO(3) |x so(3)) x SO(3) x ... x SO(3)
----------
Each element of the B list is associated with a calibration states in State's S list where the association is done
via corresponding index. In general B[i] is the SO(3) element of the symmetry group that correspond to the
state's calibration state S[i]. For example, let's assume we want to use three known direction a, b, and c, where
only the sensor that measure b is uncalibrated (we'd like to estimate the calibration states). Therefore,
the system's d list is defined as d = [b, a, c], and the state's S list is defined as S = [Sb]. The symmetry group
B list should be defined as B = [Bb] where Ba is the SO(3) element of the symmetry group that is related to Sb
----------

Definition at line 160 of file EqF.py.

Constructor & Destructor Documentation

◆ __init__()

def gtsam.examples.EqF.G.__init__ (   self,
Rot3   A = Rot3.Identity(),
np.ndarray   a = np.zeros((3, 3)),
List[Rot3]   B = None 
)
Initialize the symmetry group G

:param A: SO3 element
:param a: np.ndarray with shape (3, 3) corresponding to a skew symmetric matrix
:param B: list of SO3 elements

Definition at line 176 of file EqF.py.

Member Function Documentation

◆ __mul__()

"G" gtsam.examples.EqF.G.__mul__ (   self,
"G"  other 
)
Define the group operation

:param other: G
:return: A element of the group G given by the "multiplication" of self and other

Definition at line 203 of file EqF.py.

◆ exp()

"G" gtsam.examples.EqF.G.exp ( np.ndarray  x)
Return a group element X given by X = exp(x) where x is a numpy array

:param x: A numpy array
:return: A element of the group G given by the exponential of x

Definition at line 249 of file EqF.py.

◆ identity()

def gtsam.examples.EqF.G.identity ( int  n)
static
Return the identity of the symmetry group with n elements of SO3 related to sensor calibration states

:param n: number of elements in list B associated with calibration states
:return: The identity of the group G

Definition at line 219 of file EqF.py.

◆ inv()

"G" gtsam.examples.EqF.G.inv (   self)
Return the inverse element of the symmetry group

:return: A element of the group G given by the inverse of self

Definition at line 272 of file EqF.py.

◆ Rot3LeftJacobian()

np.ndarray gtsam.examples.EqF.G.Rot3LeftJacobian ( np.ndarray  arr)
static
Return the SO(3) Left Jacobian
:param arr: A numpy array with size 3
:return: The left Jacobian of SO(3)

Definition at line 229 of file EqF.py.

Member Data Documentation

◆ A

gtsam.examples.EqF.G.A

Definition at line 186 of file EqF.py.

◆ a

gtsam.examples.EqF.G.a

Definition at line 189 of file EqF.py.

◆ B

gtsam.examples.EqF.G.B

Definition at line 191 of file EqF.py.


The documentation for this class was generated from the following file:


gtsam
Author(s):
autogenerated on Wed May 28 2025 03:15:32