ProductLieGroup.h
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------1------------------------------------------- */
11 
19 #pragma once
20 
21 #include <gtsam/base/Lie.h>
22 #include <utility> // pair
23 
24 namespace gtsam {
25 
28 template<typename G, typename H>
29 class ProductLieGroup: public std::pair<G, H> {
32  typedef std::pair<G, H> Base;
33 
34 protected:
37 
38 public:
41 
42  // Construct from two subgroup elements
43  ProductLieGroup(const G& g, const H& h):Base(g,h) {}
44 
45  // Construct from base
47 
52 
54  return ProductLieGroup(traits<G>::Compose(this->first,other.first),
55  traits<H>::Compose(this->second,other.second));
56  }
58  return ProductLieGroup(traits<G>::Inverse(this->first), traits<H>::Inverse(this->second));
59  }
61  return (*this) * g;
62  }
64  return this->inverse() * g;
65  }
67 
71  inline static size_t Dim() {return dimension;}
72  inline size_t dim() const {return dimension;}
73 
76 
78  ChartJacobian H1 = {}, ChartJacobian H2 = {}) const {
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>());
82  return ProductLieGroup(g,h);
83  }
85  ChartJacobian H1 = {}, ChartJacobian H2 = {}) const {
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);
90  v << v1, v2;
91  return v;
92  }
94 
97 protected:
101 
102 public:
104  ChartJacobian H2 = {}) const {
105  Jacobian1 D_g_first; Jacobian2 D_h_second;
106  G g = traits<G>::Compose(this->first,other.first, H1 ? &D_g_first : 0);
107  H h = traits<H>::Compose(this->second,other.second, H1 ? &D_h_second : 0);
108  if (H1) {
109  H1->setZero();
110  H1->template topLeftCorner<dimension1,dimension1>() = D_g_first;
111  H1->template bottomRightCorner<dimension2,dimension2>() = D_h_second;
112  }
113  if (H2) *H2 = Jacobian::Identity();
114  return ProductLieGroup(g,h);
115  }
117  ChartJacobian H2 = {}) const {
118  Jacobian1 D_g_first; Jacobian2 D_h_second;
119  G g = traits<G>::Between(this->first,other.first, H1 ? &D_g_first : 0);
120  H h = traits<H>::Between(this->second,other.second, H1 ? &D_h_second : 0);
121  if (H1) {
122  H1->setZero();
123  H1->template topLeftCorner<dimension1,dimension1>() = D_g_first;
124  H1->template bottomRightCorner<dimension2,dimension2>() = D_h_second;
125  }
126  if (H2) *H2 = Jacobian::Identity();
127  return ProductLieGroup(g,h);
128  }
130  Jacobian1 D_g_first; Jacobian2 D_h_second;
131  G g = traits<G>::Inverse(this->first, D ? &D_g_first : 0);
132  H h = traits<H>::Inverse(this->second, D ? &D_h_second : 0);
133  if (D) {
134  D->setZero();
135  D->template topLeftCorner<dimension1,dimension1>() = D_g_first;
136  D->template bottomRightCorner<dimension2,dimension2>() = D_h_second;
137  }
138  return ProductLieGroup(g,h);
139  }
141  Jacobian1 D_g_first; Jacobian2 D_h_second;
142  G g = traits<G>::Expmap(v.template head<dimension1>(), Hv ? &D_g_first : 0);
143  H h = traits<H>::Expmap(v.template tail<dimension2>(), Hv ? &D_h_second : 0);
144  if (Hv) {
145  Hv->setZero();
146  Hv->template topLeftCorner<dimension1,dimension1>() = D_g_first;
147  Hv->template bottomRightCorner<dimension2,dimension2>() = D_h_second;
148  }
149  return ProductLieGroup(g,h);
150  }
152  Jacobian1 D_g_first; Jacobian2 D_h_second;
153  typename traits<G>::TangentVector v1 = traits<G>::Logmap(p.first, Hp ? &D_g_first : 0);
154  typename traits<H>::TangentVector v2 = traits<H>::Logmap(p.second, Hp ? &D_h_second : 0);
156  v << v1, v2;
157  if (Hp) {
158  Hp->setZero();
159  Hp->template topLeftCorner<dimension1,dimension1>() = D_g_first;
160  Hp->template bottomRightCorner<dimension2,dimension2>() = D_h_second;
161  }
162  return v;
163  }
165  return Logmap(p, Hp);
166  }
169  }
172  }
174 
175 };
176 
177 // Define any direct product group to be a model of the multiplicative Group concept
178 template<typename G, typename H>
179 struct traits<ProductLieGroup<G, H> > : internal::LieGroupTraits<ProductLieGroup<G, H> > {};
180 
181 } // namespace gtsam
182 
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
Definition: gnuplot_common_settings.hh:74
gtsam::ProductLieGroup::between
ProductLieGroup between(const ProductLieGroup &g) const
Definition: ProductLieGroup.h:63
gtsam::ProductLieGroup::localCoordinates
TangentVector localCoordinates(const ProductLieGroup &g, ChartJacobian H1={}, ChartJacobian H2={}) const
Definition: ProductLieGroup.h:84
base
Annotation indicating that a class derives from another given type.
Definition: attr.h:64
gtsam::ProductLieGroup::dimension2
@ dimension2
Definition: ProductLieGroup.h:36
D
MatrixXcd D
Definition: EigenSolver_EigenSolver_MatrixType.cpp:14
gtsam::ProductLieGroup::Jacobian
Eigen::Matrix< double, dimension, dimension > Jacobian
Definition: ProductLieGroup.h:98
pybind_wrapper_test_script.this
this
Definition: pybind_wrapper_test_script.py:38
gtsam::ProductLieGroup::compose
ProductLieGroup compose(const ProductLieGroup &g) const
Definition: ProductLieGroup.h:60
gtsam::ProductLieGroup::ProductLieGroup
ProductLieGroup(const Base &base)
Definition: ProductLieGroup.h:46
gtsam::ProductLieGroup::dimension1
@ dimension1
Definition: ProductLieGroup.h:35
h
const double h
Definition: testSimpleHelicopter.cpp:19
gtsam::ProductLieGroup::ChartJacobian
OptionalJacobian< dimension, dimension > ChartJacobian
Definition: ProductLieGroup.h:75
gtsam::ProductLieGroup::LocalCoordinates
static TangentVector LocalCoordinates(const ProductLieGroup &p, ChartJacobian Hp={})
Definition: ProductLieGroup.h:164
gtsam::multiplicative_group_tag
Group operator syntax flavors.
Definition: Group.h:33
Expmap
Pose2_ Expmap(const Vector3_ &xi)
Definition: InverseKinematicsExampleExpressions.cpp:47
gtsam::ProductLieGroup::operator*
ProductLieGroup operator*(const ProductLieGroup &other) const
Definition: ProductLieGroup.h:53
gtsam::ProductLieGroup::inverse
ProductLieGroup inverse(ChartJacobian D) const
Definition: ProductLieGroup.h:129
gtsam::ProductLieGroup::between
ProductLieGroup between(const ProductLieGroup &other, ChartJacobian H1, ChartJacobian H2={}) const
Definition: ProductLieGroup.h:116
gtsam::IsLieGroup
Definition: Lie.h:260
gtsam::ProductLieGroup::Jacobian2
Eigen::Matrix< double, dimension2, dimension2 > Jacobian2
Definition: ProductLieGroup.h:100
gtsam::ProductLieGroup::dim
size_t dim() const
Definition: ProductLieGroup.h:72
gtsam::internal::LieGroupTraits
Definition: Lie.h:174
gtsam::ProductLieGroup::compose
ProductLieGroup compose(const ProductLieGroup &other, ChartJacobian H1, ChartJacobian H2={}) const
Definition: ProductLieGroup.h:103
gtsam::ProductLieGroup::Identity
static ProductLieGroup Identity()
Definition: ProductLieGroup.h:51
gtsam::ProductLieGroup::expmap
ProductLieGroup expmap(const TangentVector &v) const
Definition: ProductLieGroup.h:167
gtsam::ProductLieGroup::Expmap
static ProductLieGroup Expmap(const TangentVector &v, ChartJacobian Hv={})
Definition: ProductLieGroup.h:140
gtsam::ProductLieGroup::Dim
static size_t Dim()
Definition: ProductLieGroup.h:71
g
void g(const string &key, int i)
Definition: testBTree.cpp:41
Between
BetweenFactor< Rot3 > Between
Definition: testRot3Optimization.cpp:31
gtsam::ProductLieGroup::retract
ProductLieGroup retract(const TangentVector &v, ChartJacobian H1={}, ChartJacobian H2={}) const
Definition: ProductLieGroup.h:77
Lie.h
Base class and basic functions for Lie types.
gtsam
traits
Definition: chartTesting.h:28
gtsam::ProductLieGroup::logmap
TangentVector logmap(const ProductLieGroup &g) const
Definition: ProductLieGroup.h:170
gtsam::ProductLieGroup
Definition: ProductLieGroup.h:29
gtsam::ProductLieGroup::ProductLieGroup
ProductLieGroup(const G &g, const H &h)
Definition: ProductLieGroup.h:43
gtsam::ProductLieGroup::inverse
ProductLieGroup inverse() const
Definition: ProductLieGroup.h:57
gtsam::traits
Definition: Group.h:36
gtsam::ProductLieGroup::Logmap
static TangentVector Logmap(const ProductLieGroup &p, ChartJacobian Hp={})
Definition: ProductLieGroup.h:151
gtsam::OptionalJacobian
Definition: OptionalJacobian.h:38
gtsam::ProductLieGroup::GTSAM_CONCEPT_ASSERT
GTSAM_CONCEPT_ASSERT(IsLieGroup< G >)
p
float * p
Definition: Tutorial_Map_using.cpp:9
G
JacobiRotation< float > G
Definition: Jacobi_makeGivens.cpp:2
v2
Vector v2
Definition: testSerializationBase.cpp:39
v
Array< int, Dynamic, 1 > v
Definition: Array_initializer_list_vector_cxx11.cpp:1
gtsam::ProductLieGroup::Jacobian1
Eigen::Matrix< double, dimension1, dimension1 > Jacobian1
Definition: ProductLieGroup.h:99
Eigen::Matrix
The matrix class, also used for vectors and row-vectors.
Definition: 3rdparty/Eigen/Eigen/src/Core/Matrix.h:178
Base
Definition: test_virtual_functions.cpp:156
gtsam::ProductLieGroup::dimension
@ dimension
Definition: ProductLieGroup.h:70
gtsam::ProductLieGroup::group_flavor
multiplicative_group_tag group_flavor
Definition: ProductLieGroup.h:50
pybind_wrapper_test_script.other
other
Definition: pybind_wrapper_test_script.py:42
gtsam::ProductLieGroup::Base
std::pair< G, H > Base
Definition: ProductLieGroup.h:32
v1
Vector v1
Definition: testSerializationBase.cpp:38
gtsam::ProductLieGroup::ProductLieGroup
ProductLieGroup()
Default constructor yields identity.
Definition: ProductLieGroup.h:40
gtsam::ProductLieGroup::TangentVector
Eigen::Matrix< double, dimension, 1 > TangentVector
Definition: ProductLieGroup.h:74


gtsam
Author(s):
autogenerated on Tue Jun 25 2024 03:02:24