diff --git a/gtsam/geometry/geometry.i b/gtsam/geometry/geometry.i index 988727b98..2171e1882 100644 --- a/gtsam/geometry/geometry.i +++ b/gtsam/geometry/geometry.i @@ -1123,7 +1123,7 @@ class StereoCamera { #include class TriangulationResult { enum Status { VALID, DEGENERATE, BEHIND_CAMERA, OUTLIER, FAR_POINT }; - Status status; + gtsam::TriangulationResult::Status status; TriangulationResult(const gtsam::Point3& p); const gtsam::Point3& get() const; static gtsam::TriangulationResult Degenerate(); @@ -1142,7 +1142,7 @@ class TriangulationParameters { bool enableEPI; double landmarkDistanceThreshold; double dynamicOutlierRejectionThreshold; - SharedNoiseModel noiseModel; + gtsam::SharedNoiseModel noiseModel; TriangulationParameters(const double rankTolerance = 1.0, const bool enableEPI = false, double landmarkDistanceThreshold = -1, diff --git a/gtsam/inference/inference.i b/gtsam/inference/inference.i index fbdd70fdf..d4c90e356 100644 --- a/gtsam/inference/inference.i +++ b/gtsam/inference/inference.i @@ -168,7 +168,7 @@ class DotWriter { std::map variablePositions; std::map positionHints; - std::set boxes; + std::set boxes; std::map factorPositions; }; diff --git a/gtsam/nonlinear/nonlinear.i b/gtsam/nonlinear/nonlinear.i index 55966ee84..ae72f5d7e 100644 --- a/gtsam/nonlinear/nonlinear.i +++ b/gtsam/nonlinear/nonlinear.i @@ -32,8 +32,8 @@ class GraphvizFormatting : gtsam::DotWriter { GraphvizFormatting(); enum Axis { X, Y, Z, NEGX, NEGY, NEGZ }; - Axis paperHorizontalAxis; - Axis paperVerticalAxis; + gtsam::GraphvizFormatting::Axis paperHorizontalAxis; + gtsam::GraphvizFormatting::Axis paperVerticalAxis; double scale; bool mergeSimilarFactors; @@ -522,13 +522,13 @@ template virtual class GncParams { GncParams(const PARAMS& baseOptimizerParams); GncParams(); - BaseOptimizerParameters baseOptimizerParams; + PARAMS baseOptimizerParams; gtsam::GncLossType lossType; size_t maxIterations; double muStep; double relativeCostTol; double weightsTol; - Verbosity verbosity; + This::Verbosity verbosity; gtsam::KeyVector knownInliers; gtsam::KeyVector knownOutliers; @@ -680,7 +680,7 @@ class ISAM2Params { bool findUnusedFactorSlots; enum Factorization { CHOLESKY, QR }; - Factorization factorization; + gtsam::ISAM2Params::Factorization factorization; }; class ISAM2Clique {