fix template bug
parent
b7a502ea04
commit
055e027632
|
@ -322,9 +322,7 @@ template <T = {gtsam::Point2, gtsam::Rot2, gtsam::Pose2, gtsam::Point3,
|
||||||
virtual class KarcherMeanFactor : gtsam::NonlinearFactor {
|
virtual class KarcherMeanFactor : gtsam::NonlinearFactor {
|
||||||
KarcherMeanFactor(const gtsam::KeyVector& keys);
|
KarcherMeanFactor(const gtsam::KeyVector& keys);
|
||||||
};
|
};
|
||||||
|
const gtsam::Rot3 FindKarcherMean<gtsam::Rot3>(const std::vector<gtsam::Rot3>& rotations);
|
||||||
template <T = {gtsam::Rot3}>
|
|
||||||
const T FindKarcherMean<T>(const std::vector<T>& rotations);
|
|
||||||
|
|
||||||
#include <gtsam/slam/FrobeniusFactor.h>
|
#include <gtsam/slam/FrobeniusFactor.h>
|
||||||
gtsam::noiseModel::Isotropic* ConvertNoiseModel(gtsam::noiseModel::Base* model,
|
gtsam::noiseModel::Isotropic* ConvertNoiseModel(gtsam::noiseModel::Base* model,
|
||||||
|
|
Loading…
Reference in New Issue