KarcherMeanFactor.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  * -------------------------------------------------------------------------- */
11 
12 /*
13  * @file KarcherMeanFactor.h
14  * @author Frank Dellaert
15  * @date March 2019
16  */
17 
18 #pragma once
19 
20 #include <gtsam/base/Matrix.h>
22 
23 #include <map>
24 #include <vector>
25 #include <optional>
26 
27 namespace gtsam {
33 template <class T>
34 typename std::enable_if<traits<T>::IsLieGroup, T>::type
35 FindKarcherMean(const std::vector<T, Eigen::aligned_allocator<T>> &elements);
36 
38 template <class T>
39 typename std::enable_if<traits<T>::IsLieGroup, T>::type
40 FindKarcherMean(std::initializer_list<T> &&elements);
41 
50 template <class T> class KarcherMeanFactor : public NonlinearFactor {
51  // Compile time dimension: can be -1
52  inline constexpr static auto D = traits<T>::dimension;
53 
54  // Runtime dimension: always >=0
55  size_t d_;
56 
58  std::shared_ptr<JacobianFactor> whitenedJacobian_;
59 
60 public:
66  template <typename CONTAINER>
67  KarcherMeanFactor(const CONTAINER &keys, int d = D,
68  std::optional<double> beta = {});
69 
71  ~KarcherMeanFactor() override {}
72 
74  double error(const Values &c) const override { return 0; }
75 
77  size_t dim() const override { return d_; }
78 
80  std::shared_ptr<GaussianFactor> linearize(const Values &c) const override {
81  return whitenedJacobian_;
82  }
83 };
84 // \KarcherMeanFactor
85 } // namespace gtsam
d
static const double d[K][N]
Definition: igam.h:11
c
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
Matrix.h
typedef and functions to augment Eigen's MatrixXd
gtsam::FindKarcherMean
T FindKarcherMean(const std::vector< T > &rotations)
Definition: KarcherMeanFactor-inl.h:45
gtsam::KarcherMeanFactor::whitenedJacobian_
std::shared_ptr< JacobianFactor > whitenedJacobian_
Constant Jacobian made of d*d identity matrices.
Definition: KarcherMeanFactor.h:58
type
Definition: pytypes.h:1527
beta
double beta(double a, double b)
Definition: beta.c:61
gtsam::KarcherMeanFactor
Definition: KarcherMeanFactor.h:50
gtsam::KarcherMeanFactor::~KarcherMeanFactor
~KarcherMeanFactor() override
Destructor.
Definition: KarcherMeanFactor.h:71
Eigen::aligned_allocator
STL compatible allocator to use with types requiring a non standrad alignment.
Definition: Memory.h:878
gtsam::KarcherMeanFactor::error
double error(const Values &c) const override
Calculate the error of the factor: always zero.
Definition: KarcherMeanFactor.h:74
Eigen::Triplet
A small structure to hold a non zero as a triplet (i,j,value).
Definition: SparseUtil.h:162
JacobianFactor.h
gtsam
traits
Definition: ABC.h:17
gtsam::traits
Definition: Group.h:36
gtsam::Values
Definition: Values.h:65
gtsam::Factor::keys
const KeyVector & keys() const
Access the factor's involved variable keys.
Definition: Factor.h:143
gtsam::KarcherMeanFactor::KarcherMeanFactor
KarcherMeanFactor(const CONTAINER &keys, int d=D, std::optional< double > beta={})
Definition: KarcherMeanFactor-inl.h:61
gtsam::NonlinearFactor
Definition: NonlinearFactor.h:69
gtsam::KarcherMeanFactor::D
constexpr static auto D
Definition: KarcherMeanFactor.h:52
gtsam::KarcherMeanFactor::d_
size_t d_
Definition: KarcherMeanFactor.h:55
gtsam::KarcherMeanFactor::dim
size_t dim() const override
get the dimension of the factor (number of rows on linearization)
Definition: KarcherMeanFactor.h:77
gtsam::KarcherMeanFactor::linearize
std::shared_ptr< GaussianFactor > linearize(const Values &c) const override
linearize to a GaussianFactor
Definition: KarcherMeanFactor.h:80


gtsam
Author(s):
autogenerated on Wed May 28 2025 03:01:37