Fix return type wrapping for Matlab wrapper
parent
2bfd480a0e
commit
e5ef9c2cc0
|
@ -1123,7 +1123,7 @@ class StereoCamera {
|
||||||
#include <gtsam/geometry/triangulation.h>
|
#include <gtsam/geometry/triangulation.h>
|
||||||
class TriangulationResult {
|
class TriangulationResult {
|
||||||
enum Status { VALID, DEGENERATE, BEHIND_CAMERA, OUTLIER, FAR_POINT };
|
enum Status { VALID, DEGENERATE, BEHIND_CAMERA, OUTLIER, FAR_POINT };
|
||||||
Status status;
|
gtsam::TriangulationResult::Status status;
|
||||||
TriangulationResult(const gtsam::Point3& p);
|
TriangulationResult(const gtsam::Point3& p);
|
||||||
const gtsam::Point3& get() const;
|
const gtsam::Point3& get() const;
|
||||||
static gtsam::TriangulationResult Degenerate();
|
static gtsam::TriangulationResult Degenerate();
|
||||||
|
@ -1142,7 +1142,7 @@ class TriangulationParameters {
|
||||||
bool enableEPI;
|
bool enableEPI;
|
||||||
double landmarkDistanceThreshold;
|
double landmarkDistanceThreshold;
|
||||||
double dynamicOutlierRejectionThreshold;
|
double dynamicOutlierRejectionThreshold;
|
||||||
SharedNoiseModel noiseModel;
|
gtsam::SharedNoiseModel noiseModel;
|
||||||
TriangulationParameters(const double rankTolerance = 1.0,
|
TriangulationParameters(const double rankTolerance = 1.0,
|
||||||
const bool enableEPI = false,
|
const bool enableEPI = false,
|
||||||
double landmarkDistanceThreshold = -1,
|
double landmarkDistanceThreshold = -1,
|
||||||
|
|
|
@ -168,7 +168,7 @@ class DotWriter {
|
||||||
|
|
||||||
std::map<gtsam::Key, gtsam::Vector2> variablePositions;
|
std::map<gtsam::Key, gtsam::Vector2> variablePositions;
|
||||||
std::map<char, double> positionHints;
|
std::map<char, double> positionHints;
|
||||||
std::set<Key> boxes;
|
std::set<gtsam::Key> boxes;
|
||||||
std::map<size_t, gtsam::Vector2> factorPositions;
|
std::map<size_t, gtsam::Vector2> factorPositions;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
|
@ -32,8 +32,8 @@ class GraphvizFormatting : gtsam::DotWriter {
|
||||||
GraphvizFormatting();
|
GraphvizFormatting();
|
||||||
|
|
||||||
enum Axis { X, Y, Z, NEGX, NEGY, NEGZ };
|
enum Axis { X, Y, Z, NEGX, NEGY, NEGZ };
|
||||||
Axis paperHorizontalAxis;
|
gtsam::GraphvizFormatting::Axis paperHorizontalAxis;
|
||||||
Axis paperVerticalAxis;
|
gtsam::GraphvizFormatting::Axis paperVerticalAxis;
|
||||||
|
|
||||||
double scale;
|
double scale;
|
||||||
bool mergeSimilarFactors;
|
bool mergeSimilarFactors;
|
||||||
|
@ -522,13 +522,13 @@ template<PARAMS>
|
||||||
virtual class GncParams {
|
virtual class GncParams {
|
||||||
GncParams(const PARAMS& baseOptimizerParams);
|
GncParams(const PARAMS& baseOptimizerParams);
|
||||||
GncParams();
|
GncParams();
|
||||||
BaseOptimizerParameters baseOptimizerParams;
|
PARAMS baseOptimizerParams;
|
||||||
gtsam::GncLossType lossType;
|
gtsam::GncLossType lossType;
|
||||||
size_t maxIterations;
|
size_t maxIterations;
|
||||||
double muStep;
|
double muStep;
|
||||||
double relativeCostTol;
|
double relativeCostTol;
|
||||||
double weightsTol;
|
double weightsTol;
|
||||||
Verbosity verbosity;
|
This::Verbosity verbosity;
|
||||||
gtsam::KeyVector knownInliers;
|
gtsam::KeyVector knownInliers;
|
||||||
gtsam::KeyVector knownOutliers;
|
gtsam::KeyVector knownOutliers;
|
||||||
|
|
||||||
|
@ -680,7 +680,7 @@ class ISAM2Params {
|
||||||
bool findUnusedFactorSlots;
|
bool findUnusedFactorSlots;
|
||||||
|
|
||||||
enum Factorization { CHOLESKY, QR };
|
enum Factorization { CHOLESKY, QR };
|
||||||
Factorization factorization;
|
gtsam::ISAM2Params::Factorization factorization;
|
||||||
};
|
};
|
||||||
|
|
||||||
class ISAM2Clique {
|
class ISAM2Clique {
|
||||||
|
|
Loading…
Reference in New Issue