fix templating TODOs
parent
2340f1aa09
commit
80a052d048
|
@ -1181,8 +1181,8 @@ class TriangulationParameters {
|
||||||
const gtsam::SharedNoiseModel& noiseModel = nullptr);
|
const gtsam::SharedNoiseModel& noiseModel = nullptr);
|
||||||
};
|
};
|
||||||
|
|
||||||
// Templates appear not yet supported for free functions - issue raised at
|
// Can be templated but overloaded for convenience.
|
||||||
// borglab/wrap#14 to add support
|
// We can now call `triangulatePoint3` with any template type.
|
||||||
|
|
||||||
// Cal3_S2 versions
|
// Cal3_S2 versions
|
||||||
gtsam::Point3 triangulatePoint3(const gtsam::Pose3Vector& poses,
|
gtsam::Point3 triangulatePoint3(const gtsam::Pose3Vector& poses,
|
||||||
|
|
|
@ -176,13 +176,9 @@ class DotWriter {
|
||||||
class VariableIndex {
|
class VariableIndex {
|
||||||
// Standard Constructors and Named Constructors
|
// Standard Constructors and Named Constructors
|
||||||
VariableIndex();
|
VariableIndex();
|
||||||
// TODO: Templetize constructor when wrap supports it
|
template <T = {gtsam::SymbolicFactorGraph, gtsam::GaussianFactorGraph,
|
||||||
// template<T = {gtsam::FactorGraph}>
|
gtsam::NonlinearFactorGraph}>
|
||||||
// VariableIndex(const T& factorGraph, size_t nVariables);
|
VariableIndex(const T& factorGraph);
|
||||||
// VariableIndex(const T& factorGraph);
|
|
||||||
VariableIndex(const gtsam::SymbolicFactorGraph& sfg);
|
|
||||||
VariableIndex(const gtsam::GaussianFactorGraph& gfg);
|
|
||||||
VariableIndex(const gtsam::NonlinearFactorGraph& fg);
|
|
||||||
VariableIndex(const gtsam::VariableIndex& other);
|
VariableIndex(const gtsam::VariableIndex& other);
|
||||||
|
|
||||||
// Testable
|
// Testable
|
||||||
|
|
|
@ -126,39 +126,16 @@ class BinaryMeasurementsRot3 {
|
||||||
#include <gtsam/slam/dataset.h>
|
#include <gtsam/slam/dataset.h>
|
||||||
#include <gtsam/sfm/ShonanAveraging.h>
|
#include <gtsam/sfm/ShonanAveraging.h>
|
||||||
|
|
||||||
// TODO(frank): copy/pasta below until we have integer template parameters in
|
template <d={2, 3}>
|
||||||
// wrap!
|
class ShonanAveragingParameters {
|
||||||
|
ShonanAveragingParameters(const gtsam::LevenbergMarquardtParams& lm);
|
||||||
class ShonanAveragingParameters2 {
|
ShonanAveragingParameters(const gtsam::LevenbergMarquardtParams& lm,
|
||||||
ShonanAveragingParameters2(const gtsam::LevenbergMarquardtParams& lm);
|
|
||||||
ShonanAveragingParameters2(const gtsam::LevenbergMarquardtParams& lm,
|
|
||||||
string method);
|
string method);
|
||||||
gtsam::LevenbergMarquardtParams getLMParams() const;
|
gtsam::LevenbergMarquardtParams getLMParams() const;
|
||||||
void setOptimalityThreshold(double value);
|
void setOptimalityThreshold(double value);
|
||||||
double getOptimalityThreshold() const;
|
double getOptimalityThreshold() const;
|
||||||
void setAnchor(size_t index, const gtsam::Rot2& value);
|
void setAnchor(size_t index, const gtsam::This::Rot& value);
|
||||||
pair<size_t, gtsam::Rot2> getAnchor();
|
pair<size_t, gtsam::This::Rot> getAnchor();
|
||||||
void setAnchorWeight(double value);
|
|
||||||
double getAnchorWeight() const;
|
|
||||||
void setKarcherWeight(double value);
|
|
||||||
double getKarcherWeight() const;
|
|
||||||
void setGaugesWeight(double value);
|
|
||||||
double getGaugesWeight() const;
|
|
||||||
void setUseHuber(bool value);
|
|
||||||
bool getUseHuber() const;
|
|
||||||
void setCertifyOptimality(bool value);
|
|
||||||
bool getCertifyOptimality() const;
|
|
||||||
};
|
|
||||||
|
|
||||||
class ShonanAveragingParameters3 {
|
|
||||||
ShonanAveragingParameters3(const gtsam::LevenbergMarquardtParams& lm);
|
|
||||||
ShonanAveragingParameters3(const gtsam::LevenbergMarquardtParams& lm,
|
|
||||||
string method);
|
|
||||||
gtsam::LevenbergMarquardtParams getLMParams() const;
|
|
||||||
void setOptimalityThreshold(double value);
|
|
||||||
double getOptimalityThreshold() const;
|
|
||||||
void setAnchor(size_t index, const gtsam::Rot3& value);
|
|
||||||
pair<size_t, gtsam::Rot3> getAnchor();
|
|
||||||
void setAnchorWeight(double value);
|
void setAnchorWeight(double value);
|
||||||
double getAnchorWeight() const;
|
double getAnchorWeight() const;
|
||||||
void setKarcherWeight(double value);
|
void setKarcherWeight(double value);
|
||||||
|
@ -171,6 +148,7 @@ class ShonanAveragingParameters3 {
|
||||||
bool getCertifyOptimality() const;
|
bool getCertifyOptimality() const;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
// NOTE(Varun): Not templated because each class has specializations defined.
|
||||||
class ShonanAveraging2 {
|
class ShonanAveraging2 {
|
||||||
ShonanAveraging2(string g2oFile);
|
ShonanAveraging2(string g2oFile);
|
||||||
ShonanAveraging2(string g2oFile,
|
ShonanAveraging2(string g2oFile,
|
||||||
|
@ -217,10 +195,9 @@ class ShonanAveraging2 {
|
||||||
};
|
};
|
||||||
|
|
||||||
class ShonanAveraging3 {
|
class ShonanAveraging3 {
|
||||||
ShonanAveraging3(
|
ShonanAveraging3(const gtsam::This::Measurements& measurements,
|
||||||
const std::vector<gtsam::BinaryMeasurement<gtsam::Rot3>>& measurements,
|
const gtsam::ShonanAveragingParameters3& parameters =
|
||||||
const gtsam::ShonanAveragingParameters3& parameters =
|
gtsam::ShonanAveragingParameters3());
|
||||||
gtsam::ShonanAveragingParameters3());
|
|
||||||
ShonanAveraging3(string g2oFile);
|
ShonanAveraging3(string g2oFile);
|
||||||
ShonanAveraging3(string g2oFile,
|
ShonanAveraging3(string g2oFile,
|
||||||
const gtsam::ShonanAveragingParameters3& parameters);
|
const gtsam::ShonanAveragingParameters3& parameters);
|
||||||
|
|
|
@ -21,7 +21,6 @@ using namespace gtsam;
|
||||||
|
|
||||||
int main(int argc, char *argv[]) {
|
int main(int argc, char *argv[]) {
|
||||||
|
|
||||||
// FIXME: ticPush_ does not exist
|
|
||||||
{
|
{
|
||||||
gttic_(top1);
|
gttic_(top1);
|
||||||
gttic_(sub1);
|
gttic_(sub1);
|
||||||
|
|
Loading…
Reference in New Issue