Go to the documentation of this file.
28 template<
typename G,
typename H>
32 typedef std::pair<G, H>
Base;
79 if (H1||H2)
throw std::runtime_error(
"ProductLieGroup::retract derivatives not implemented yet");
80 G g = traits<G>::Retract(this->first,
v.template head<dimension1>());
81 H h = traits<H>::Retract(this->second,
v.template tail<dimension2>());
86 if (H1||H2)
throw std::runtime_error(
"ProductLieGroup::localCoordinates derivatives not implemented yet");
87 typename traits<G>::TangentVector
v1 = traits<G>::Local(this->first,
g.first);
88 typename traits<H>::TangentVector
v2 = traits<H>::Local(this->second,
g.second);
110 H1->template topLeftCorner<dimension1,dimension1>() = D_g_first;
111 H1->template bottomRightCorner<dimension2,dimension2>() = D_h_second;
113 if (H2) *H2 = Jacobian::Identity();
123 H1->template topLeftCorner<dimension1,dimension1>() = D_g_first;
124 H1->template bottomRightCorner<dimension2,dimension2>() = D_h_second;
126 if (H2) *H2 = Jacobian::Identity();
135 D->template topLeftCorner<dimension1,dimension1>() = D_g_first;
136 D->template bottomRightCorner<dimension2,dimension2>() = D_h_second;
146 Hv->template topLeftCorner<dimension1,dimension1>() = D_g_first;
147 Hv->template bottomRightCorner<dimension2,dimension2>() = D_h_second;
159 Hp->template topLeftCorner<dimension1,dimension1>() = D_g_first;
160 Hp->template bottomRightCorner<dimension2,dimension2>() = D_h_second;
178 template<
typename G,
typename H>
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
ProductLieGroup between(const ProductLieGroup &g) const
TangentVector localCoordinates(const ProductLieGroup &g, ChartJacobian H1={}, ChartJacobian H2={}) const
Annotation indicating that a class derives from another given type.
Eigen::Matrix< double, dimension, dimension > Jacobian
ProductLieGroup compose(const ProductLieGroup &g) const
ProductLieGroup(const Base &base)
OptionalJacobian< dimension, dimension > ChartJacobian
static TangentVector LocalCoordinates(const ProductLieGroup &p, ChartJacobian Hp={})
Group operator syntax flavors.
Pose2_ Expmap(const Vector3_ &xi)
ProductLieGroup operator*(const ProductLieGroup &other) const
ProductLieGroup inverse(ChartJacobian D) const
ProductLieGroup between(const ProductLieGroup &other, ChartJacobian H1, ChartJacobian H2={}) const
Eigen::Matrix< double, dimension2, dimension2 > Jacobian2
ProductLieGroup compose(const ProductLieGroup &other, ChartJacobian H1, ChartJacobian H2={}) const
static ProductLieGroup Identity()
ProductLieGroup expmap(const TangentVector &v) const
static ProductLieGroup Expmap(const TangentVector &v, ChartJacobian Hv={})
void g(const string &key, int i)
BetweenFactor< Rot3 > Between
ProductLieGroup retract(const TangentVector &v, ChartJacobian H1={}, ChartJacobian H2={}) const
Base class and basic functions for Lie types.
TangentVector logmap(const ProductLieGroup &g) const
ProductLieGroup(const G &g, const H &h)
ProductLieGroup inverse() const
static TangentVector Logmap(const ProductLieGroup &p, ChartJacobian Hp={})
GTSAM_CONCEPT_ASSERT(IsLieGroup< G >)
JacobiRotation< float > G
Array< int, Dynamic, 1 > v
Eigen::Matrix< double, dimension1, dimension1 > Jacobian1
The matrix class, also used for vectors and row-vectors.
multiplicative_group_tag group_flavor
ProductLieGroup()
Default constructor yields identity.
Eigen::Matrix< double, dimension, 1 > TangentVector
gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:03:53