diff --git a/gtsam/slam/slam.i b/gtsam/slam/slam.i index 1e159ec5f..ef946c655 100644 --- a/gtsam/slam/slam.i +++ b/gtsam/slam/slam.i @@ -322,12 +322,7 @@ template -T FindKarcherMean(const std::vector> &rotations); -template T FindKarcherMean(std::initializer_list &&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(const Rot3Vector &rotations); typedef FindKarcherMean FindKarcherMeanRot3; -gtsam::Rot3 FindKarcherMeanRot3(const Rot3Vector& rotations); +gtsam::Rot3 FindKarcherMeanRot3(const gtsam::Rot3Vector& rotations); #include gtsam::noiseModel::Isotropic* ConvertNoiseModel(gtsam::noiseModel::Base* model,