gtsam
4.0.0
gtsam
|
True SO(3), i.e., 3*3 matrix subgroup We guarantee (all but first) constructors only generate from sub-manifold.
However, round-off errors in repeated composition could move off it...
Constructors | |
SO3 () | |
Constructor from AngleAxisd. | |
template<typename Derived > | |
SO3 (const MatrixBase< Derived > &R) | |
Constructor from Eigen Matrix. | |
SO3 (const Eigen::AngleAxisd &angleAxis) | |
Constructor from AngleAxisd. | |
static SO3 | AxisAngle (const Vector3 &axis, double theta) |
Static, named constructor TODO think about relation with above. | |
Group | |
SO3 | inverse () const |
inverse of a rotation = transpose | |
static SO3 | identity () |
identity rotation for group operation | |
Lie Group | |
Matrix3 | AdjointMap () const |
static SO3 | Expmap (const Vector3 &omega, ChartJacobian H=boost::none) |
Exponential map at identity - create a rotation from canonical coordinates \( [R_x,R_y,R_z] \) using Rodrigues' formula. | |
static Matrix3 | ExpmapDerivative (const Vector3 &omega) |
Derivative of Expmap. | |
static Vector3 | Logmap (const SO3 &R, ChartJacobian H=boost::none) |
Log map at identity - returns the canonical coordinates \( [R_x,R_y,R_z] \) of this rotation. | |
static Matrix3 | LogmapDerivative (const Vector3 &omega) |
Derivative of Logmap. More... | |
Public Member Functions | |
Testable | |
void | print (const std::string &s) const |
bool | equals (const SO3 &R, double tol) const |
![]() | |
BOOST_STATIC_ASSERT_MSG (N !=Eigen::Dynamic, "LieGroup not yet specialized for dynamically sized types.") | |
const SO3 & | derived () const |
SO3 | compose (const SO3 &g) const |
SO3 | compose (const SO3 &g, ChartJacobian H1, ChartJacobian H2=boost::none) const |
SO3 | between (const SO3 &g) const |
SO3 | between (const SO3 &g, ChartJacobian H1, ChartJacobian H2=boost::none) const |
SO3 | inverse (ChartJacobian H) const |
SO3 | expmap (const TangentVector &v) const |
expmap as required by manifold concept Applies exponential map to v and composes with *this | |
SO3 | expmap (const TangentVector &v, ChartJacobian H1, ChartJacobian H2=boost::none) const |
expmap with optional derivatives | |
TangentVector | logmap (const SO3 &g) const |
logmap as required by manifold concept Applies logarithmic map to group element that takes *this to g | |
TangentVector | logmap (const SO3 &g, ChartJacobian H1, ChartJacobian H2=boost::none) const |
logmap with optional derivatives | |
SO3 | retract (const TangentVector &v) const |
retract as required by manifold concept: applies v at *this | |
SO3 | retract (const TangentVector &v, ChartJacobian H1, ChartJacobian H2=boost::none) const |
retract with optional derivatives | |
TangentVector | localCoordinates (const SO3 &g) const |
localCoordinates as required by manifold concept: finds tangent vector between *this and g | |
TangentVector | localCoordinates (const SO3 &g, ChartJacobian H1, ChartJacobian H2=boost::none) const |
localCoordinates with optional derivatives | |
Public Types | |
enum | { dimension = 3 } |
![]() | |
enum | |
typedef OptionalJacobian< N, N > | ChartJacobian |
typedef Eigen::Matrix< double, N, N > | Jacobian |
typedef Eigen::Matrix< double, N, 1 > | TangentVector |
Classes | |
struct | ChartAtOrigin |
Additional Inherited Members | |
![]() | |
static SO3 | Retract (const TangentVector &v) |
Retract at origin: possible in Lie group because it has an identity. | |
static SO3 | Retract (const TangentVector &v, ChartJacobian H) |
Retract at origin with optional derivative. | |
static TangentVector | LocalCoordinates (const SO3 &g) |
LocalCoordinates at origin: possible in Lie group because it has an identity. | |
static TangentVector | LocalCoordinates (const SO3 &g, ChartJacobian H) |
LocalCoordinates at origin with optional derivative. | |
|
static |
Derivative of Logmap.
Right Jacobian for Log map in SO(3) - equation (10.86) and following equations in G.S. Chirikjian, "Stochastic Models, Information Theory, and Lie Groups", Volume 2, 2008. logmap( Rhat * expmap(omega) ) \approx logmap( Rhat ) + Jrinv * omega where Jrinv = LogmapDerivative(omega); This maps a perturbation on the manifold (expmap(omega)) to a perturbation in the tangent space (Jrinv * omega)