22 #include <gtsam/slam/KarcherMeanFactor.h> 29 template <
class T,
class ALLOC>
30 T FindKarcherMeanImpl(
const vector<T, ALLOC>& rotations) {
33 NonlinearFactorGraph graph;
34 static const Key kKey(0);
35 for (
const auto& R : rotations) {
36 graph.addPrior<T>(kKey, R);
39 initial.insert<T>(kKey, T());
40 auto result = GaussNewtonOptimizer(graph, initial).optimize();
41 return result.at<T>(kKey);
45 T FindKarcherMean(
const std::vector<T>& rotations) {
46 return FindKarcherMeanImpl(rotations);
50 T FindKarcherMean(
const std::vector<T, Eigen::aligned_allocator<T>>& rotations) {
51 return FindKarcherMeanImpl(rotations);
55 T FindKarcherMean(std::initializer_list<T>&& rotations) {
56 return FindKarcherMeanImpl(std::vector<T, Eigen::aligned_allocator<T> >(rotations));
60 template <
typename CONTAINER>
62 std::optional<double> beta)
65 throw std::invalid_argument(
66 "KarcherMeanFactor needs dimension for dynamic types.");
70 Matrix A = Matrix::Identity(d, d);
71 if (beta) A *= std::sqrt(*beta);
72 std::map<Key, Matrix> terms;
77 std::make_shared<JacobianFactor>(terms, Vector::Zero(d));
Factor Graph consisting of non-linear factors.
Definition: NonlinearFactor.h:68
Definition: KarcherMeanFactor.h:46
Definition: chartTesting.h:28
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102