use aligned allocator for Rot3Vector
parent
56312d91be
commit
d37881e656
|
|
@ -323,11 +323,6 @@ virtual class KarcherMeanFactor : gtsam::NonlinearFactor {
|
|||
KarcherMeanFactor(const gtsam::KeyVector& keys);
|
||||
};
|
||||
|
||||
template <class T>
|
||||
T FindKarcherMean(const std::vector<T, Eigen::aligned_allocator<T>> &rotations);
|
||||
|
||||
template <class T> T FindKarcherMean(std::initializer_list<T> &&rotations);
|
||||
|
||||
class Rot3Vector {
|
||||
Rot3Vector();
|
||||
size_t size() const;
|
||||
|
|
@ -336,8 +331,9 @@ class Rot3Vector {
|
|||
gtsam::Rot3 at(size_t i) const;
|
||||
void push_back(const gtsam::Rot3& R);
|
||||
};
|
||||
gtsam::Rot3 FindKarcherMean<gtsam::Rot3>(const Rot3Vector &rotations);
|
||||
typedef FindKarcherMean<gtsam::Rot3> FindKarcherMeanRot3;
|
||||
gtsam::Rot3 FindKarcherMeanRot3(const Rot3Vector& rotations);
|
||||
gtsam::Rot3 FindKarcherMeanRot3(const gtsam::Rot3Vector& rotations);
|
||||
|
||||
#include <gtsam/slam/FrobeniusFactor.h>
|
||||
gtsam::noiseModel::Isotropic* ConvertNoiseModel(gtsam::noiseModel::Base* model,
|
||||
|
|
|
|||
Loading…
Reference in New Issue