graphslam.pose.base_pose module
A base class for poses.
- class graphslam.pose.base_pose.BasePose[source]
Bases:
ndarray
A base class for poses.
- equals(other, tol=1e-06)[source]
Check whether two poses are equal.
- Parameters:
other (BasePose) – The pose to which we are comparing
tol (float) – The tolerance
- Returns:
Whether the two poses are equal
- Return type:
bool
- jacobian_boxplus()[source]
Compute the Jacobian of \(p_1 \boxplus \Delta \mathbf{x}\) w.r.t. \(\Delta \mathbf{x}\) evaluated at \(\Delta \mathbf{x} = \mathbf{0}\).
Let
# The dimensionality of :math:`\Delta \mathbf{x}`, which should be the same as # the compact dimensionality of `self` n_dx = self.COMPACT_DIMENSIONALITY # The dimensionality of :math:`p_1 \boxplus \Delta \mathbf{x}`, which should be # the same as the dimensionality of `self` n_boxplus = len(self.to_array())
Then the shape of the Jacobian will be
n_boxplus x n_dx
.- Returns:
The Jacobian of \(p_1 \boxplus \Delta \mathbf{x}\) w.r.t. \(\Delta \mathbf{x}\) evaluated at \(\Delta \mathbf{x} = \mathbf{0}\)
- Return type:
np.ndarray
- jacobian_inverse()[source]
Compute the Jacobian of \(p^{-1}\).
Let
# The dimensionality of `self` n_self = len(self.to_array())
Then the shape of the Jacobian will be
n_self x n_self
.- Returns:
The Jacobian of \(p^{-1}\)
- Return type:
np.ndarray
- jacobian_self_ominus_other_wrt_other(other)[source]
Compute the Jacobian of \(p_1 \ominus p_2\) w.r.t. \(p_2\).
Let
# The dimensionality of `other` n_other = len(other.to_array()) # The dimensionality of `self - other` n_ominus = len((self - other).to_array())
Then the shape of the Jacobian will be
n_ominus x n_other
.- Parameters:
other (BasePose) – The pose that is being subtracted from
self
- Returns:
The Jacobian of \(p_1 \ominus p_2\) w.r.t. \(p_2\).
- Return type:
np.ndarray
- jacobian_self_ominus_other_wrt_other_compact(other)[source]
Compute the Jacobian of \(p_1 \ominus p_2\) w.r.t. \(p_2\).
Let
# The dimensionality of `other` n_other = len(other.to_array()) # The compact dimensionality of `self - other` n_compact = (self - other).COMPACT_DIMENSIONALITY
Then the shape of the Jacobian will be
n_compact x n_other
.- Parameters:
other (BasePose) – The pose that is being subtracted from
self
- Returns:
The Jacobian of \(p_1 \ominus p_2\) w.r.t. \(p_2\).
- Return type:
np.ndarray
- jacobian_self_ominus_other_wrt_self(other)[source]
Compute the Jacobian of \(p_1 \ominus p_2\) w.r.t. \(p_1\).
Let
# The dimensionality of `self` n_self = len(self.to_array()) # The dimensionality of `self - other` n_ominus = len((self - other).to_array())
Then the shape of the Jacobian will be
n_ominus x n_self
.- Parameters:
other (BasePose) – The pose that is being subtracted from
self
- Returns:
The Jacobian of \(p_1 \ominus p_2\) w.r.t. \(p_1\).
- Return type:
np.ndarray
- jacobian_self_ominus_other_wrt_self_compact(other)[source]
Compute the Jacobian of \(p_1 \ominus p_2\) w.r.t. \(p_1\).
Let
# The dimensionality of `self` n_self = len(self.to_array()) # The compact dimensionality of `self - other` n_compact = (self - other).COMPACT_DIMENSIONALITY
Then the shape of the Jacobian will be
n_compact x n_self
.- Parameters:
other (BasePose) – The pose that is being subtracted from
self
- Returns:
The Jacobian of \(p_1 \ominus p_2\) w.r.t. \(p_1\).
- Return type:
np.ndarray
- jacobian_self_oplus_other_wrt_other(other)[source]
Compute the Jacobian of \(p_1 \oplus p_2\) w.r.t. \(p_2\).
Let
# The dimensionality of `other` n_other = len(other.to_array()) # The dimensionality of `self + other` n_oplus = len((self + other).to_array())
Then the shape of the Jacobian will be
n_oplus x n_other
.- Parameters:
other (BasePose) – The pose that is being added to
self
- Returns:
The Jacobian of \(p_1 \oplus p_2\) w.r.t. \(p_2\).
- Return type:
np.ndarray
- jacobian_self_oplus_other_wrt_other_compact(other)[source]
Compute the Jacobian of \(p_1 \oplus p_2\) w.r.t. \(p_2\).
Let
# The dimensionality of `other` n_other = len(other.to_array()) # The compact dimensionality of `self + other` n_compact = (self + other).COMPACT_DIMENSIONALITY
Then the shape of the Jacobian will be
n_compact x n_other
.- Parameters:
other (BasePose) – The pose that is being added to
self
- Returns:
The Jacobian of \(p_1 \oplus p_2\) w.r.t. \(p_2\).
- Return type:
np.ndarray
- jacobian_self_oplus_other_wrt_self(other)[source]
Compute the Jacobian of \(p_1 \oplus p_2\) w.r.t. \(p_1\).
Let
# The dimensionality of `self` n_self = len(self.to_array()) # The dimensionality of `self + other` n_oplus = len((self + other).to_array())
Then the shape of the Jacobian will be
n_oplus x n_self
.- Parameters:
other (BasePose) – The pose that is being added to
self
- Returns:
The Jacobian of \(p_1 \oplus p_2\) w.r.t. \(p_1\).
- Return type:
np.ndarray
- jacobian_self_oplus_other_wrt_self_compact(other)[source]
Compute the Jacobian of \(p_1 \oplus p_2\) w.r.t. \(p_1\).
Let
# The dimensionality of `self` n_self = len(self.to_array()) # The compact dimensionality of `self + other` n_compact = (self + other).COMPACT_DIMENSIONALITY
Then the shape of the Jacobian will be
n_compact x n_self
.- Parameters:
other (BasePose) – The pose that is being added to
self
- Returns:
The Jacobian of \(p_1 \oplus p_2\) w.r.t. \(p_1\).
- Return type:
np.ndarray
- jacobian_self_oplus_point_wrt_point(point)[source]
Compute the Jacobian of \(p_1 \oplus p_2\) w.r.t. \(p_2\), where \(p_2\) is a point.
Let
# The dimensionality of `point` n_point = len(point.to_array()) # The dimensionality of `self + point` n_oplus = len((self + point).to_array())
Then the shape of the Jacobian will be
n_oplus x n_point
.- Parameters:
point (BasePose) – The point that is being added to
self
- Returns:
The Jacobian of \(p_1 \oplus p_2\) w.r.t. \(p_2\).
- Return type:
np.ndarray
- jacobian_self_oplus_point_wrt_self(point)[source]
Compute the Jacobian of \(p_1 \oplus p_2\) w.r.t. \(p_1\), where \(p_2\) is a point.
Let
# The dimensionality of `self` n_self = len(self.to_array()) # The dimensionality of `self + point` n_oplus = len((self + point).to_array())
Then the shape of the Jacobian will be
n_oplus x n_self
.- Parameters:
point (BasePose) – The point that is being added to
self
- Returns:
The Jacobian of \(p_1 \oplus p_2\) w.r.t. \(p_1\).
- Return type:
np.ndarray
- property orientation
Return the pose’s orientation.
- Returns:
The pose’s orientation
- Return type:
float, np.ndarray
- property position
Return the pose’s position.
- Returns:
The pose’s position
- Return type:
np.ndarray