handle some TODOs
parent
f58ee917f0
commit
a763944249
|
@ -73,8 +73,7 @@ class GncParams {
|
||||||
double weightsTol = 1e-4; ///< If the weights are within weightsTol from being binary, stop iterating (only for TLS)
|
double weightsTol = 1e-4; ///< If the weights are within weightsTol from being binary, stop iterating (only for TLS)
|
||||||
Verbosity verbosity = SILENT; ///< Verbosity level
|
Verbosity verbosity = SILENT; ///< Verbosity level
|
||||||
|
|
||||||
//TODO(Varun) replace IndexVector with vector<size_t> once pybind11/stl.h is globally enabled.
|
/// Use IndexVector for inliers and outliers since it is fast
|
||||||
/// Use IndexVector for inliers and outliers since it is fast + wrapping
|
|
||||||
using IndexVector = FastVector<uint64_t>;
|
using IndexVector = FastVector<uint64_t>;
|
||||||
///< Slots in the factor graph corresponding to measurements that we know are inliers
|
///< Slots in the factor graph corresponding to measurements that we know are inliers
|
||||||
IndexVector knownInliers = IndexVector();
|
IndexVector knownInliers = IndexVector();
|
||||||
|
|
|
@ -305,8 +305,8 @@ virtual class GncParams {
|
||||||
double relativeCostTol;
|
double relativeCostTol;
|
||||||
double weightsTol;
|
double weightsTol;
|
||||||
gtsam::This::Verbosity verbosity;
|
gtsam::This::Verbosity verbosity;
|
||||||
gtsam::KeyVector knownInliers;
|
gtsam::This::IndexVector knownInliers;
|
||||||
gtsam::KeyVector knownOutliers;
|
gtsam::This::IndexVector knownOutliers;
|
||||||
|
|
||||||
void setLossType(const gtsam::GncLossType type);
|
void setLossType(const gtsam::GncLossType type);
|
||||||
void setMaxIterations(const size_t maxIter);
|
void setMaxIterations(const size_t maxIter);
|
||||||
|
@ -314,8 +314,8 @@ virtual class GncParams {
|
||||||
void setRelativeCostTol(double value);
|
void setRelativeCostTol(double value);
|
||||||
void setWeightsTol(double value);
|
void setWeightsTol(double value);
|
||||||
void setVerbosityGNC(const gtsam::This::Verbosity value);
|
void setVerbosityGNC(const gtsam::This::Verbosity value);
|
||||||
void setKnownInliers(const gtsam::KeyVector& knownIn);
|
void setKnownInliers(const gtsam::This::IndexVector& knownIn);
|
||||||
void setKnownOutliers(const gtsam::KeyVector& knownOut);
|
void setKnownOutliers(const gtsam::This::IndexVector& knownOut);
|
||||||
void print(const string& str = "GncParams: ") const;
|
void print(const string& str = "GncParams: ") const;
|
||||||
|
|
||||||
enum Verbosity {
|
enum Verbosity {
|
||||||
|
|
|
@ -225,10 +225,9 @@ class ShonanAveraging3 {
|
||||||
ShonanAveraging3(string g2oFile,
|
ShonanAveraging3(string g2oFile,
|
||||||
const gtsam::ShonanAveragingParameters3& parameters);
|
const gtsam::ShonanAveragingParameters3& parameters);
|
||||||
|
|
||||||
// TODO(frank): deprecate once we land pybind wrapper
|
|
||||||
ShonanAveraging3(const gtsam::BetweenFactorPose3s& factors);
|
|
||||||
ShonanAveraging3(const gtsam::BetweenFactorPose3s& factors,
|
ShonanAveraging3(const gtsam::BetweenFactorPose3s& factors,
|
||||||
const gtsam::ShonanAveragingParameters3& parameters);
|
const gtsam::ShonanAveragingParameters3& parameters =
|
||||||
|
gtsam::ShonanAveragingParameters3());
|
||||||
|
|
||||||
// Query properties
|
// Query properties
|
||||||
size_t nrUnknowns() const;
|
size_t nrUnknowns() const;
|
||||||
|
|
Loading…
Reference in New Issue