Go to the documentation of this file.
36 template <
class Class,
int N>
45 return static_cast<const Class&
>(*this);
58 if (H1) *H1 =
g.inverse().AdjointMap();
66 if (H1) *H1 = -
result.inverse().AdjointMap();
94 if (H1) *H1 =
g.inverse().AdjointMap();
105 if (H1) *H1 = - D_v_h *
h.inverse().AdjointMap();
112 return Class::ChartAtOrigin::Retract(
v);
117 return Class::ChartAtOrigin::Local(
g);
122 return Class::ChartAtOrigin::Retract(
v,
H);
127 return Class::ChartAtOrigin::Local(
g,
H);
132 return compose(Class::ChartAtOrigin::Retract(
v));
137 return Class::ChartAtOrigin::Local(
between(
g));
144 Class g = Class::ChartAtOrigin::Retract(
v, H2 ? &D_g_v : 0);
146 if (H1) *H1 =
g.inverse().AdjointMap();
156 TangentVector v = Class::ChartAtOrigin::Local(
h, (H1 || H2) ? &D_v_h : 0);
157 if (H1) *H1 = - D_v_h *
h.inverse().AdjointMap();
173 template<
class Class>
192 return origin.localCoordinates(
other, Horigin, Hother);
197 return origin.retract(
v, Horigin, Hv);
204 return Class::Logmap(
m, Hm);
213 return m1.compose(
m2, H1, H2);
218 return m1.between(
m2, H1, H2);
239 template<
class Class>
241 return l1.inverse().compose(
l2);
245 template<
class Class>
247 return Class::Logmap(
l0.between(lp));
251 template<
class Class>
270 "This type's trait does not assert it is a Lie group (or derived)");
299 static const double _2 = 1. / 2., _12 = 1. / 12., _24 = 1. / 24.;
326 template <
typename T>
334 typename traits<T>::TangentVector
delta = traits<T>::Logmap(
between, log_H);
336 const T result = traits<T>::Compose(
337 X, Delta, compose_H_x);
339 if (Hx) *Hx = compose_H_x +
t * exp_H * log_H * between_H_x;
340 if (Hy) *Hy =
t * exp_H * log_H;
343 return traits<T>::Compose(
358 typename T::Jacobian
operator()(
const typename T::Jacobian &covariance)
372 #define GTSAM_CONCEPT_LIE_INST(T) template class gtsam::IsLieGroup<T>;
373 #define GTSAM_CONCEPT_LIE_TYPE(T) using _gtsam_IsLieGroup_##T = gtsam::IsLieGroup<T>;
Class between(const Class &g) const
constexpr static auto dimension
Matrix wedge(const Vector &x)
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics set mxtics default set mytics default set mx2tics default set my2tics default set xtics border mirror norotate autofreq set ytics border mirror norotate autofreq set ztics border nomirror norotate autofreq set nox2tics set noy2tics set timestamp bottom norotate set rrange[*:*] noreverse nowriteback set trange[*:*] noreverse nowriteback set urange[*:*] noreverse nowriteback set vrange[*:*] noreverse nowriteback set xlabel matrix size set x2label set timefmt d m y n H
traits< T >::ManifoldType ManifoldType
OptionalJacobian< dimension, dimension > ChartJacobian
Class retract(const TangentVector &v, ChartJacobian H1, ChartJacobian H2={}) const
retract with optional derivatives
Expression< T > between(const Expression< T > &t1, const Expression< T > &t2)
static const double d[K][N]
Eigen::Matrix< double, N, N > Jacobian
Class expmap(const TangentVector &v, ChartJacobian H1, ChartJacobian H2={}) const
expmap with optional derivatives
OptionalJacobian< N, N > ChartJacobian
GaussianFactorGraphValuePair Y
traits< T >::structure_category structure_category_tag
multiplicative_group_tag group_flavor
T expm(const Vector &x, int K=7)
Class compose(const Class &g) const
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
Concept check class for variable types with Group properties.
static TangentVector Logmap(const Class &m, ChartJacobian Hm={})
Eigen::Triplet< double > T
traits< T >::ChartJacobian ChartJacobian
TangentVector logmap(const Class &g, ChartJacobian H1, ChartJacobian H2={}) const
logmap with optional derivatives
Class between_default(const Class &l1, const Class &l2)
T BCH(const T &X, const T &Y)
AGC: bracket() only appears in Rot3 tests, should this be used elsewhere?
Vector logmap_default(const Class &l0, const Class &lp)
Group operator syntax flavors.
AngularVelocity bracket(const AngularVelocity &X, const AngularVelocity &Y)
Pose2_ Expmap(const Vector3_ &xi)
TangentVector localCoordinates(const Class &g, ChartJacobian H1, ChartJacobian H2={}) const
localCoordinates with optional derivatives
static Class Retract(const TangentVector &v)
Retract at origin: possible in Lie group because it has an identity.
static TangentVector LocalCoordinates(const Class &g, ChartJacobian H)
LocalCoordinates at origin with optional derivative.
constexpr static auto dimension
static TangentVector Local(const Class &origin, const Class &other, ChartJacobian Horigin={}, ChartJacobian Hother={})
Eigen::Matrix< double, N, 1 > TangentVector
Extra manifold traits for fixed-dimension types.
OptionalJacobian< traits< T >::dimension, traits< A >::dimension > type
Both LieGroupTraits and Testable.
traits< T >::TangentVector TangentVector
T interpolate(const T &X, const T &Y, double t, typename MakeOptionalJacobian< T, T >::type Hx={}, typename MakeOptionalJacobian< T, T >::type Hy={})
constexpr static auto dimension
Base class and basic functions for Manifold types.
static Class Expmap(const TangentVector &v, ChartJacobian Hv={})
TangentVector localCoordinates(const Class &g) const
localCoordinates as required by manifold concept: finds tangent vector between *this and g
TangentVector logmap(const Class &g) const
void g(const string &key, int i)
Eigen::Matrix< double, traits< T >::dimension, traits< A >::dimension > type
static Class Between(const Class &m1, const Class &m2, ChartJacobian H1={}, ChartJacobian H2={})
BetweenFactor< Rot3 > Between
tag to assert a type is a manifold
static Class Retract(const Class &origin, const TangentVector &v, ChartJacobian Horigin={}, ChartJacobian Hv={})
static Class Retract(const TangentVector &v, ChartJacobian H)
Retract at origin with optional derivative.
lie_group_tag structure_category
tag to assert a type is a group
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set origin
static Class Compose(const Class &m1, const Class &m2, ChartJacobian H1={}, ChartJacobian H2={})
tag to assert a type is a Lie group
Array< int, Dynamic, 1 > v
Class retract(const TangentVector &v) const
retract as required by manifold concept: applies v at *this
Eigen::Matrix< double, dimension, 1 > TangentVector
const Class & derived() const
Class expmap(const TangentVector &v) const
Class compose(const Class &g, ChartJacobian H1, ChartJacobian H2={}) const
static TangentVector LocalCoordinates(const Class &g)
LocalCoordinates at origin: possible in Lie group because it has an identity.
static Class Inverse(const Class &m, ChartJacobian H={})
BOOST_CONCEPT_USAGE(IsLieGroup)
Class between(const Class &g, ChartJacobian H1, ChartJacobian H2={}) const
Class inverse(ChartJacobian H) const
Class expmap_default(const Class &t, const Vector &d)
gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:11:55