28 template<
typename G,
typename H>
32 typedef std::pair<G, H> Base;
64 return this->inverse() * g;
70 enum {dimension = dimension1 + dimension2};
71 inline static size_t Dim() {
return dimension;}
72 inline size_t dim()
const {
return dimension;}
74 typedef Eigen::Matrix<double, dimension, 1> TangentVector;
78 ChartJacobian H1 = {}, ChartJacobian H2 = {})
const {
79 if (H1||H2)
throw std::runtime_error(
"ProductLieGroup::retract derivatives not implemented yet");
85 ChartJacobian H1 = {}, ChartJacobian H2 = {})
const {
86 if (H1||H2)
throw std::runtime_error(
"ProductLieGroup::localCoordinates derivatives not implemented yet");
98 typedef Eigen::Matrix<double, dimension, dimension> Jacobian;
99 typedef Eigen::Matrix<double, dimension1, dimension1> Jacobian1;
100 typedef Eigen::Matrix<double, dimension2, dimension2> Jacobian2;
104 ChartJacobian H2 = {})
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 = {})
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;
140 static ProductLieGroup Expmap(
const TangentVector& v, ChartJacobian Hv = {}) {
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;
151 static TangentVector Logmap(
const ProductLieGroup& p, ChartJacobian Hp = {}) {
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;
164 static TangentVector LocalCoordinates(
const ProductLieGroup& p, ChartJacobian Hp = {}) {
165 return Logmap(p, Hp);
168 return compose(ProductLieGroup::Expmap(v));
171 return ProductLieGroup::Logmap(between(g));
178 template<
typename G,
typename H>
ProductLieGroup()
Default constructor yields identity.
Definition: ProductLieGroup.h:40
Group operator syntax flavors.
Definition: Group.h:40
Definition: ProductLieGroup.h:29
Base class and basic functions for Lie types.
Definition: chartTesting.h:28
Definition: OptionalJacobian.h:38