28 template<
typename G,
typename H>
32 typedef std::pair<G, H>
Base;
78 ChartJacobian H1 = boost::none, ChartJacobian H2 = boost::none)
const {
79 if (H1||H2)
throw std::runtime_error(
"ProductLieGroup::retract derivatives not implemented yet");
85 ChartJacobian H1 = boost::none, ChartJacobian H2 = boost::none)
const {
86 if (H1||H2)
throw std::runtime_error(
"ProductLieGroup::localCoordinates derivatives not implemented yet");
104 ChartJacobian H2 = boost::none)
const {
105 Jacobian1 D_g_first; Jacobian2 D_h_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();
117 ChartJacobian H2 = boost::none)
const {
118 Jacobian1 D_g_first; Jacobian2 D_h_second;
123 H1->template topLeftCorner<dimension1,dimension1>() = D_g_first;
124 H1->template bottomRightCorner<dimension2,dimension2>() = D_h_second;
126 if (H2) *H2 = Jacobian::Identity();
130 Jacobian1 D_g_first; Jacobian2 D_h_second;
135 D->template topLeftCorner<dimension1,dimension1>() = D_g_first;
136 D->template bottomRightCorner<dimension2,dimension2>() = D_h_second;
141 Jacobian1 D_g_first; Jacobian2 D_h_second;
146 Hv->template topLeftCorner<dimension1,dimension1>() = D_g_first;
147 Hv->template bottomRightCorner<dimension2,dimension2>() = D_h_second;
152 Jacobian1 D_g_first; Jacobian2 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>
static ProductLieGroup identity()
ProductLieGroup inverse() const
ProductLieGroup inverse(ChartJacobian D) const
Eigen::Matrix< double, dimension1, dimension1 > Jacobian1
ProductLieGroup operator*(const ProductLieGroup &other) const
JacobiRotation< float > G
multiplicative_group_tag group_flavor
ProductLieGroup(const G &g, const H &h)
Eigen::Matrix< double, dimension, dimension > Jacobian
ProductLieGroup between(const ProductLieGroup &other, ChartJacobian H1, ChartJacobian H2=boost::none) const
static ProductLieGroup Expmap(const TangentVector &v, ChartJacobian Hv=boost::none)
Pose2_ Expmap(const Vector3_ &xi)
ProductLieGroup()
Default constructor yields identity.
TangentVector logmap(const ProductLieGroup &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 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
void g(const string &key, int i)
ProductLieGroup retract(const TangentVector &v, ChartJacobian H1=boost::none, ChartJacobian H2=boost::none) const
static TangentVector Logmap(const ProductLieGroup &p, ChartJacobian Hp=boost::none)
constexpr int first(int i)
Implementation details for constexpr functions.
ProductLieGroup expmap(const TangentVector &v) const
ProductLieGroup(const Base &base)
OptionalJacobian< dimension, dimension > ChartJacobian
static TangentVector LocalCoordinates(const ProductLieGroup &p, ChartJacobian Hp=boost::none)
Group operator syntax flavors.
BetweenFactor< Rot3 > Between
Base class and basic functions for Lie types.
ProductLieGroup compose(const ProductLieGroup &g) const
TangentVector localCoordinates(const ProductLieGroup &g, ChartJacobian H1=boost::none, ChartJacobian H2=boost::none) const
ProductLieGroup compose(const ProductLieGroup &other, ChartJacobian H1, ChartJacobian H2=boost::none) const
Eigen::Matrix< double, dimension2, dimension2 > Jacobian2
ProductLieGroup between(const ProductLieGroup &g) const
Eigen::Matrix< double, dimension, 1 > TangentVector
Annotation indicating that a class derives from another given type.
The matrix class, also used for vectors and row-vectors.
BOOST_CONCEPT_ASSERT((IsLieGroup< G >))