diff --git a/examples/LocalizationExample.cpp b/examples/LocalizationExample.cpp index e6a0f6622..33fe96ed8 100644 --- a/examples/LocalizationExample.cpp +++ b/examples/LocalizationExample.cpp @@ -78,7 +78,7 @@ class UnaryFactor: public NoiseModelFactor1 { UnaryFactor(Key j, double x, double y, const SharedNoiseModel& model): NoiseModelFactor1(model, j), mx_(x), my_(y) {} - virtual ~UnaryFactor() {} + ~UnaryFactor() override {} // Using the NoiseModelFactor1 base class there are two functions that must be overridden. // The first is the 'evaluateError' function. This function implements the desired measurement diff --git a/gtsam/base/GenericValue.h b/gtsam/base/GenericValue.h index 0e928765f..e3d6ae39c 100644 --- a/gtsam/base/GenericValue.h +++ b/gtsam/base/GenericValue.h @@ -74,7 +74,7 @@ public: } /// Destructor - virtual ~GenericValue() { + ~GenericValue() override { } /// equals implementing generic Value interface diff --git a/gtsam/base/ThreadsafeException.h b/gtsam/base/ThreadsafeException.h index 744759f5b..8d5115a19 100644 --- a/gtsam/base/ThreadsafeException.h +++ b/gtsam/base/ThreadsafeException.h @@ -72,7 +72,7 @@ protected: } /// Default destructor doesn't have the noexcept - virtual ~ThreadsafeException() noexcept { + ~ThreadsafeException() noexcept override { } public: @@ -114,7 +114,7 @@ class CholeskyFailed : public gtsam::ThreadsafeException { public: CholeskyFailed() noexcept {} - virtual ~CholeskyFailed() noexcept {} + ~CholeskyFailed() noexcept override {} }; } // namespace gtsam diff --git a/gtsam/discrete/DecisionTree-inl.h b/gtsam/discrete/DecisionTree-inl.h index dd10500e6..80b226e3a 100644 --- a/gtsam/discrete/DecisionTree-inl.h +++ b/gtsam/discrete/DecisionTree-inl.h @@ -155,7 +155,7 @@ namespace gtsam { public: - virtual ~Choice() { + ~Choice() override { #ifdef DT_DEBUG_MEMORY std::std::cout << Node::nrNodes << " destructing (Choice) " << this->id() << std::std::endl; #endif diff --git a/gtsam/geometry/Cal3Bundler.h b/gtsam/geometry/Cal3Bundler.h index 0016ded2d..0d7c1be9d 100644 --- a/gtsam/geometry/Cal3Bundler.h +++ b/gtsam/geometry/Cal3Bundler.h @@ -60,7 +60,7 @@ class GTSAM_EXPORT Cal3Bundler : public Cal3 { double tol = 1e-5) : Cal3(f, f, 0, u0, v0), k1_(k1), k2_(k2), tol_(tol) {} - virtual ~Cal3Bundler() {} + ~Cal3Bundler() override {} /// @} /// @name Testable @@ -141,7 +141,7 @@ class GTSAM_EXPORT Cal3Bundler : public Cal3 { /// @{ /// return DOF, dimensionality of tangent space - virtual size_t dim() const override { return Dim(); } + size_t dim() const override { return Dim(); } /// return DOF, dimensionality of tangent space inline static size_t Dim() { return dimension; } diff --git a/gtsam/geometry/Cal3DS2.h b/gtsam/geometry/Cal3DS2.h index 58d35c2ec..f756cba5e 100644 --- a/gtsam/geometry/Cal3DS2.h +++ b/gtsam/geometry/Cal3DS2.h @@ -47,7 +47,7 @@ class GTSAM_EXPORT Cal3DS2 : public Cal3DS2_Base { double k2, double p1 = 0.0, double p2 = 0.0, double tol = 1e-5) : Base(fx, fy, s, u0, v0, k1, k2, p1, p2, tol) {} - virtual ~Cal3DS2() {} + ~Cal3DS2() override {} /// @} /// @name Advanced Constructors @@ -80,7 +80,7 @@ class GTSAM_EXPORT Cal3DS2 : public Cal3DS2_Base { Vector localCoordinates(const Cal3DS2& T2) const; /// Return dimensions of calibration manifold object - virtual size_t dim() const override { return Dim(); } + size_t dim() const override { return Dim(); } /// Return dimensions of calibration manifold object inline static size_t Dim() { return dimension; } diff --git a/gtsam/geometry/Cal3DS2_Base.h b/gtsam/geometry/Cal3DS2_Base.h index 23e138838..a9b09cf46 100644 --- a/gtsam/geometry/Cal3DS2_Base.h +++ b/gtsam/geometry/Cal3DS2_Base.h @@ -62,7 +62,7 @@ class GTSAM_EXPORT Cal3DS2_Base : public Cal3 { p2_(p2), tol_(tol) {} - virtual ~Cal3DS2_Base() {} + ~Cal3DS2_Base() override {} /// @} /// @name Advanced Constructors @@ -132,7 +132,7 @@ class GTSAM_EXPORT Cal3DS2_Base : public Cal3 { Matrix29 D2d_calibration(const Point2& p) const; /// return DOF, dimensionality of tangent space - virtual size_t dim() const override { return Dim(); } + size_t dim() const override { return Dim(); } /// return DOF, dimensionality of tangent space inline static size_t Dim() { return dimension; } diff --git a/gtsam/geometry/Cal3Fisheye.h b/gtsam/geometry/Cal3Fisheye.h index a394d2000..a8c9fa182 100644 --- a/gtsam/geometry/Cal3Fisheye.h +++ b/gtsam/geometry/Cal3Fisheye.h @@ -73,7 +73,7 @@ class GTSAM_EXPORT Cal3Fisheye : public Cal3 { k4_(k4), tol_(tol) {} - virtual ~Cal3Fisheye() {} + ~Cal3Fisheye() override {} /// @} /// @name Advanced Constructors @@ -142,7 +142,7 @@ class GTSAM_EXPORT Cal3Fisheye : public Cal3 { const Cal3Fisheye& cal); /// print with optional string - virtual void print(const std::string& s = "") const override; + void print(const std::string& s = "") const override; /// assert equality up to a tolerance bool equals(const Cal3Fisheye& K, double tol = 10e-9) const; @@ -152,7 +152,7 @@ class GTSAM_EXPORT Cal3Fisheye : public Cal3 { /// @{ /// Return dimensions of calibration manifold object - virtual size_t dim() const override { return Dim(); } + size_t dim() const override { return Dim(); } /// Return dimensions of calibration manifold object inline static size_t Dim() { return dimension; } diff --git a/gtsam/geometry/Cal3Unified.h b/gtsam/geometry/Cal3Unified.h index ee388c8c1..f07ca0a54 100644 --- a/gtsam/geometry/Cal3Unified.h +++ b/gtsam/geometry/Cal3Unified.h @@ -62,7 +62,7 @@ class GTSAM_EXPORT Cal3Unified : public Cal3DS2_Base { double k2, double p1 = 0.0, double p2 = 0.0, double xi = 0.0) : Base(fx, fy, s, u0, v0, k1, k2, p1, p2), xi_(xi) {} - virtual ~Cal3Unified() {} + ~Cal3Unified() override {} /// @} /// @name Advanced Constructors @@ -127,7 +127,7 @@ class GTSAM_EXPORT Cal3Unified : public Cal3DS2_Base { Vector localCoordinates(const Cal3Unified& T2) const; /// Return dimensions of calibration manifold object - virtual size_t dim() const override { return Dim(); } + size_t dim() const override { return Dim(); } /// Return dimensions of calibration manifold object inline static size_t Dim() { return dimension; } diff --git a/gtsam/geometry/PinholeCamera.h b/gtsam/geometry/PinholeCamera.h index cf449ce8c..ecff766e2 100644 --- a/gtsam/geometry/PinholeCamera.h +++ b/gtsam/geometry/PinholeCamera.h @@ -157,7 +157,7 @@ public: /// @name Standard Interface /// @{ - virtual ~PinholeCamera() { + ~PinholeCamera() override { } /// return pose diff --git a/gtsam/geometry/PinholePose.h b/gtsam/geometry/PinholePose.h index 3bf96c08b..1b5a06609 100644 --- a/gtsam/geometry/PinholePose.h +++ b/gtsam/geometry/PinholePose.h @@ -352,7 +352,7 @@ public: /// @name Standard Interface /// @{ - virtual ~PinholePose() { + ~PinholePose() override { } /// return shared pointer to calibration diff --git a/gtsam/inference/inferenceExceptions.h b/gtsam/inference/inferenceExceptions.h index 4409b16c7..bcd986983 100644 --- a/gtsam/inference/inferenceExceptions.h +++ b/gtsam/inference/inferenceExceptions.h @@ -29,7 +29,7 @@ namespace gtsam { class InconsistentEliminationRequested : public std::exception { public: InconsistentEliminationRequested() noexcept {} - virtual ~InconsistentEliminationRequested() noexcept {} + ~InconsistentEliminationRequested() noexcept override {} const char* what() const noexcept override { return "An inference algorithm was called with inconsistent arguments. The\n" diff --git a/gtsam/linear/HessianFactor.h b/gtsam/linear/HessianFactor.h index a4de46104..0f4c993fe 100644 --- a/gtsam/linear/HessianFactor.h +++ b/gtsam/linear/HessianFactor.h @@ -183,7 +183,7 @@ namespace gtsam { : HessianFactor(factors, Scatter(factors)) {} /** Destructor */ - virtual ~HessianFactor() {} + ~HessianFactor() override {} /** Clone this HessianFactor */ GaussianFactor::shared_ptr clone() const override { diff --git a/gtsam/linear/JacobianFactor.h b/gtsam/linear/JacobianFactor.h index 49c47c7f0..4d4480d32 100644 --- a/gtsam/linear/JacobianFactor.h +++ b/gtsam/linear/JacobianFactor.h @@ -183,7 +183,7 @@ namespace gtsam { const VariableSlots& p_variableSlots); /** Virtual destructor */ - virtual ~JacobianFactor() {} + ~JacobianFactor() override {} /** Clone this JacobianFactor */ GaussianFactor::shared_ptr clone() const override { diff --git a/gtsam/linear/LossFunctions.h b/gtsam/linear/LossFunctions.h index 771992e80..4705721a0 100644 --- a/gtsam/linear/LossFunctions.h +++ b/gtsam/linear/LossFunctions.h @@ -129,7 +129,7 @@ class GTSAM_EXPORT Null : public Base { typedef boost::shared_ptr shared_ptr; Null(const ReweightScheme reweight = Block) : Base(reweight) {} - ~Null() {} + ~Null() override {} double weight(double /*error*/) const override { return 1.0; } double loss(double distance) const override { return 0.5 * distance * distance; } void print(const std::string &s) const override; @@ -286,7 +286,7 @@ class GTSAM_EXPORT GemanMcClure : public Base { typedef boost::shared_ptr shared_ptr; GemanMcClure(double c = 1.0, const ReweightScheme reweight = Block); - ~GemanMcClure() {} + ~GemanMcClure() override {} double weight(double distance) const override; double loss(double distance) const override; void print(const std::string &s) const override; @@ -316,7 +316,7 @@ class GTSAM_EXPORT DCS : public Base { typedef boost::shared_ptr shared_ptr; DCS(double c = 1.0, const ReweightScheme reweight = Block); - ~DCS() {} + ~DCS() override {} double weight(double distance) const override; double loss(double distance) const override; void print(const std::string &s) const override; diff --git a/gtsam/linear/NoiseModel.h b/gtsam/linear/NoiseModel.h index a9b46bd16..2fb54d329 100644 --- a/gtsam/linear/NoiseModel.h +++ b/gtsam/linear/NoiseModel.h @@ -188,7 +188,7 @@ namespace gtsam { typedef boost::shared_ptr shared_ptr; - virtual ~Gaussian() {} + ~Gaussian() override {} /** * A Gaussian noise model created by specifying a square root information matrix. @@ -300,7 +300,7 @@ namespace gtsam { typedef boost::shared_ptr shared_ptr; - virtual ~Diagonal() {} + ~Diagonal() override {} /** * A diagonal noise model created by specifying a Vector of sigmas, i.e. @@ -406,7 +406,7 @@ namespace gtsam { typedef boost::shared_ptr shared_ptr; - ~Constrained() {} + ~Constrained() override {} /// true if a constrained noise mode, saves slow/clumsy dynamic casting bool isConstrained() const override { return true; } @@ -536,7 +536,7 @@ namespace gtsam { public: - virtual ~Isotropic() {} + ~Isotropic() override {} typedef boost::shared_ptr shared_ptr; @@ -600,7 +600,7 @@ namespace gtsam { typedef boost::shared_ptr shared_ptr; - ~Unit() {} + ~Unit() override {} /** * Create a unit covariance noise model @@ -671,7 +671,7 @@ namespace gtsam { : Base(noise->dim()), robust_(robust), noise_(noise) {} /// Destructor - ~Robust() {} + ~Robust() override {} void print(const std::string& name) const override; bool equals(const Base& expected, double tol=1e-9) const override; diff --git a/gtsam/linear/PCGSolver.h b/gtsam/linear/PCGSolver.h index 515f2eed2..198b77ec8 100644 --- a/gtsam/linear/PCGSolver.h +++ b/gtsam/linear/PCGSolver.h @@ -72,7 +72,7 @@ protected: public: /* Interface to initialize a solver without a problem */ PCGSolver(const PCGSolverParameters &p); - virtual ~PCGSolver() { + ~PCGSolver() override { } using IterativeSolver::optimize; diff --git a/gtsam/linear/Preconditioner.h b/gtsam/linear/Preconditioner.h index eceb19982..3a406c0a5 100644 --- a/gtsam/linear/Preconditioner.h +++ b/gtsam/linear/Preconditioner.h @@ -96,7 +96,7 @@ struct GTSAM_EXPORT DummyPreconditionerParameters : public PreconditionerParamet typedef PreconditionerParameters Base; typedef boost::shared_ptr shared_ptr; DummyPreconditionerParameters() : Base() {} - virtual ~DummyPreconditionerParameters() {} + ~DummyPreconditionerParameters() override {} }; /*******************************************************************************************/ @@ -108,7 +108,7 @@ public: public: DummyPreconditioner() : Base() {} - virtual ~DummyPreconditioner() {} + ~DummyPreconditioner() override {} /* Computation Interfaces for raw vector */ void solve(const Vector& y, Vector &x) const override { x = y; } @@ -124,7 +124,7 @@ public: struct GTSAM_EXPORT BlockJacobiPreconditionerParameters : public PreconditionerParameters { typedef PreconditionerParameters Base; BlockJacobiPreconditionerParameters() : Base() {} - virtual ~BlockJacobiPreconditionerParameters() {} + ~BlockJacobiPreconditionerParameters() override {} }; /*******************************************************************************************/ @@ -132,7 +132,7 @@ class GTSAM_EXPORT BlockJacobiPreconditioner : public Preconditioner { public: typedef Preconditioner Base; BlockJacobiPreconditioner() ; - virtual ~BlockJacobiPreconditioner() ; + ~BlockJacobiPreconditioner() override ; /* Computation Interfaces for raw vector */ void solve(const Vector& y, Vector &x) const override; diff --git a/gtsam/linear/SubgraphPreconditioner.h b/gtsam/linear/SubgraphPreconditioner.h index 8906337a9..681c12e40 100644 --- a/gtsam/linear/SubgraphPreconditioner.h +++ b/gtsam/linear/SubgraphPreconditioner.h @@ -80,7 +80,7 @@ namespace gtsam { SubgraphPreconditioner(const sharedFG& Ab2, const sharedBayesNet& Rc1, const sharedValues& xbar, const SubgraphPreconditionerParameters &p = SubgraphPreconditionerParameters()); - virtual ~SubgraphPreconditioner() {} + ~SubgraphPreconditioner() override {} /** print the object */ void print(const std::string& s = "SubgraphPreconditioner") const; diff --git a/gtsam/linear/SubgraphSolver.h b/gtsam/linear/SubgraphSolver.h index 3c5f79cfc..a41738321 100644 --- a/gtsam/linear/SubgraphSolver.h +++ b/gtsam/linear/SubgraphSolver.h @@ -111,7 +111,7 @@ class GTSAM_EXPORT SubgraphSolver : public IterativeSolver { const Parameters ¶meters); /// Destructor - virtual ~SubgraphSolver() {} + ~SubgraphSolver() override {} /// @} /// @name Implement interface diff --git a/gtsam/linear/linearExceptions.h b/gtsam/linear/linearExceptions.h index f0ad0be39..72981613e 100644 --- a/gtsam/linear/linearExceptions.h +++ b/gtsam/linear/linearExceptions.h @@ -95,7 +95,7 @@ namespace gtsam { Key j_; public: IndeterminantLinearSystemException(Key j) noexcept : j_(j) {} - virtual ~IndeterminantLinearSystemException() noexcept {} + ~IndeterminantLinearSystemException() noexcept override {} Key nearbyVariable() const { return j_; } const char* what() const noexcept override; }; @@ -110,7 +110,7 @@ namespace gtsam { InvalidNoiseModel(DenseIndex factorDims, DenseIndex noiseModelDims) : factorDims(factorDims), noiseModelDims(noiseModelDims) {} - virtual ~InvalidNoiseModel() noexcept {} + ~InvalidNoiseModel() noexcept override {} const char* what() const noexcept override; @@ -128,7 +128,7 @@ namespace gtsam { InvalidMatrixBlock(DenseIndex factorRows, DenseIndex blockRows) : factorRows(factorRows), blockRows(blockRows) {} - virtual ~InvalidMatrixBlock() noexcept {} + ~InvalidMatrixBlock() noexcept override {} const char* what() const noexcept override; diff --git a/gtsam/navigation/AHRSFactor.h b/gtsam/navigation/AHRSFactor.h index 34626fcf6..1ab2d7cdc 100644 --- a/gtsam/navigation/AHRSFactor.h +++ b/gtsam/navigation/AHRSFactor.h @@ -154,7 +154,7 @@ public: AHRSFactor(Key rot_i, Key rot_j, Key bias, const PreintegratedAhrsMeasurements& preintegratedMeasurements); - virtual ~AHRSFactor() { + ~AHRSFactor() override { } /// @return a deep copy of this factor diff --git a/gtsam/navigation/AttitudeFactor.h b/gtsam/navigation/AttitudeFactor.h index 9a0a11cfb..23fbbca89 100644 --- a/gtsam/navigation/AttitudeFactor.h +++ b/gtsam/navigation/AttitudeFactor.h @@ -92,7 +92,7 @@ public: Rot3AttitudeFactor() { } - virtual ~Rot3AttitudeFactor() { + ~Rot3AttitudeFactor() override { } /** @@ -166,7 +166,7 @@ public: Pose3AttitudeFactor() { } - virtual ~Pose3AttitudeFactor() { + ~Pose3AttitudeFactor() override { } /** diff --git a/gtsam/navigation/CombinedImuFactor.h b/gtsam/navigation/CombinedImuFactor.h index efca25bff..0aeeabc22 100644 --- a/gtsam/navigation/CombinedImuFactor.h +++ b/gtsam/navigation/CombinedImuFactor.h @@ -173,7 +173,7 @@ public: } /// Virtual destructor - virtual ~PreintegratedCombinedMeasurements() {} + ~PreintegratedCombinedMeasurements() override {} /// @} @@ -291,7 +291,7 @@ public: Key pose_i, Key vel_i, Key pose_j, Key vel_j, Key bias_i, Key bias_j, const PreintegratedCombinedMeasurements& preintegratedMeasurements); - virtual ~CombinedImuFactor() {} + ~CombinedImuFactor() override {} /// @return a deep copy of this factor gtsam::NonlinearFactor::shared_ptr clone() const override; diff --git a/gtsam/navigation/GPSFactor.h b/gtsam/navigation/GPSFactor.h index e6d5b88a9..f6469346e 100644 --- a/gtsam/navigation/GPSFactor.h +++ b/gtsam/navigation/GPSFactor.h @@ -51,7 +51,7 @@ public: /** default constructor - only use for serialization */ GPSFactor(): nT_(0, 0, 0) {} - virtual ~GPSFactor() {} + ~GPSFactor() override {} /** * @brief Constructor from a measurement in a Cartesian frame. @@ -129,7 +129,7 @@ public: /// default constructor - only use for serialization GPSFactor2():nT_(0, 0, 0) {} - virtual ~GPSFactor2() {} + ~GPSFactor2() override {} /// Constructor from a measurement in a Cartesian frame. GPSFactor2(Key key, const Point3& gpsIn, const SharedNoiseModel& model) : diff --git a/gtsam/navigation/ImuFactor.h b/gtsam/navigation/ImuFactor.h index cd9c591f1..29bdb2a99 100644 --- a/gtsam/navigation/ImuFactor.h +++ b/gtsam/navigation/ImuFactor.h @@ -107,7 +107,7 @@ public: } /// Virtual destructor - virtual ~PreintegratedImuMeasurements() { + ~PreintegratedImuMeasurements() override { } /// print @@ -196,7 +196,7 @@ public: ImuFactor(Key pose_i, Key vel_i, Key pose_j, Key vel_j, Key bias, const PreintegratedImuMeasurements& preintegratedMeasurements); - virtual ~ImuFactor() { + ~ImuFactor() override { } /// @return a deep copy of this factor @@ -274,7 +274,7 @@ public: ImuFactor2(Key state_i, Key state_j, Key bias, const PreintegratedImuMeasurements& preintegratedMeasurements); - virtual ~ImuFactor2() { + ~ImuFactor2() override { } /// @return a deep copy of this factor diff --git a/gtsam/navigation/TangentPreintegration.h b/gtsam/navigation/TangentPreintegration.h index 1b51b4e1e..56b0a1c75 100644 --- a/gtsam/navigation/TangentPreintegration.h +++ b/gtsam/navigation/TangentPreintegration.h @@ -54,7 +54,7 @@ public: const imuBias::ConstantBias& biasHat = imuBias::ConstantBias()); /// Virtual destructor - virtual ~TangentPreintegration() { + ~TangentPreintegration() override { } /// @} diff --git a/gtsam/nonlinear/DoglegOptimizer.h b/gtsam/nonlinear/DoglegOptimizer.h index 6b3097476..e278bf075 100644 --- a/gtsam/nonlinear/DoglegOptimizer.h +++ b/gtsam/nonlinear/DoglegOptimizer.h @@ -43,7 +43,7 @@ public: DoglegParams() : deltaInitial(1.0), verbosityDL(SILENT) {} - virtual ~DoglegParams() {} + ~DoglegParams() override {} void print(const std::string& str = "") const override { NonlinearOptimizerParams::print(str); @@ -103,7 +103,7 @@ public: /// @{ /** Virtual destructor */ - virtual ~DoglegOptimizer() {} + ~DoglegOptimizer() override {} /** * Perform a single iteration, returning GaussianFactorGraph corresponding to @@ -121,7 +121,7 @@ public: protected: /** Access the parameters (base class version) */ - virtual const NonlinearOptimizerParams& _params() const override { return params_; } + const NonlinearOptimizerParams& _params() const override { return params_; } /** Internal function for computing a COLAMD ordering if no ordering is specified */ DoglegParams ensureHasOrdering(DoglegParams params, const NonlinearFactorGraph& graph) const; diff --git a/gtsam/nonlinear/ExpressionFactor.h b/gtsam/nonlinear/ExpressionFactor.h index 6d6162825..b55d643aa 100644 --- a/gtsam/nonlinear/ExpressionFactor.h +++ b/gtsam/nonlinear/ExpressionFactor.h @@ -71,7 +71,7 @@ protected: } /// Destructor - virtual ~ExpressionFactor() {} + ~ExpressionFactor() override {} /** return the measurement */ const T& measured() const { return measured_; } @@ -245,7 +245,7 @@ public: using ArrayNKeys = std::array; /// Destructor - virtual ~ExpressionFactorN() = default; + ~ExpressionFactorN() override = default; // Don't provide backward compatible evaluateVector(), due to its problematic // variable length of optional Jacobian arguments. Vector evaluateError(const @@ -330,7 +330,7 @@ public: throw std::runtime_error( "ExpressionFactor2::expression not provided: cannot deserialize."); } - virtual Expression + Expression expression(const typename ExpressionFactorN::ArrayNKeys &keys) const override { return expression(keys[0], keys[1]); diff --git a/gtsam/nonlinear/FunctorizedFactor.h b/gtsam/nonlinear/FunctorizedFactor.h index 53a48f097..691ab8ac8 100644 --- a/gtsam/nonlinear/FunctorizedFactor.h +++ b/gtsam/nonlinear/FunctorizedFactor.h @@ -79,7 +79,7 @@ class GTSAM_EXPORT FunctorizedFactor : public NoiseModelFactor1 { const std::function)> func) : Base(model, key), measured_(z), noiseModel_(model), func_(func) {} - virtual ~FunctorizedFactor() {} + ~FunctorizedFactor() override {} /// @return a deep copy of this factor NonlinearFactor::shared_ptr clone() const override { @@ -183,7 +183,7 @@ class GTSAM_EXPORT FunctorizedFactor2 : public NoiseModelFactor2 { noiseModel_(model), func_(func) {} - virtual ~FunctorizedFactor2() {} + ~FunctorizedFactor2() override {} /// @return a deep copy of this factor NonlinearFactor::shared_ptr clone() const override { diff --git a/gtsam/nonlinear/GaussNewtonOptimizer.h b/gtsam/nonlinear/GaussNewtonOptimizer.h index a3923524b..1c40f7fa5 100644 --- a/gtsam/nonlinear/GaussNewtonOptimizer.h +++ b/gtsam/nonlinear/GaussNewtonOptimizer.h @@ -70,7 +70,7 @@ public: /// @{ /** Virtual destructor */ - virtual ~GaussNewtonOptimizer() {} + ~GaussNewtonOptimizer() override {} /** * Perform a single iteration, returning GaussianFactorGraph corresponding to diff --git a/gtsam/nonlinear/LevenbergMarquardtOptimizer.h b/gtsam/nonlinear/LevenbergMarquardtOptimizer.h index 2f09f234d..3e4453f4f 100644 --- a/gtsam/nonlinear/LevenbergMarquardtOptimizer.h +++ b/gtsam/nonlinear/LevenbergMarquardtOptimizer.h @@ -69,7 +69,7 @@ public: const LevenbergMarquardtParams& params = LevenbergMarquardtParams()); /** Virtual destructor */ - virtual ~LevenbergMarquardtOptimizer() { + ~LevenbergMarquardtOptimizer() override { } /// @} diff --git a/gtsam/nonlinear/LevenbergMarquardtParams.h b/gtsam/nonlinear/LevenbergMarquardtParams.h index 30e783fc9..1e2c6e395 100644 --- a/gtsam/nonlinear/LevenbergMarquardtParams.h +++ b/gtsam/nonlinear/LevenbergMarquardtParams.h @@ -122,7 +122,7 @@ public: return params; } - virtual ~LevenbergMarquardtParams() {} + ~LevenbergMarquardtParams() override {} void print(const std::string& str = "") const override; /// @name Getters/Setters, mainly for wrappers. Use fields above in C++. diff --git a/gtsam/nonlinear/NonlinearConjugateGradientOptimizer.h b/gtsam/nonlinear/NonlinearConjugateGradientOptimizer.h index a85f27425..fd9e49a62 100644 --- a/gtsam/nonlinear/NonlinearConjugateGradientOptimizer.h +++ b/gtsam/nonlinear/NonlinearConjugateGradientOptimizer.h @@ -67,7 +67,7 @@ public: const Values& initialValues, const Parameters& params = Parameters()); /// Destructor - virtual ~NonlinearConjugateGradientOptimizer() { + ~NonlinearConjugateGradientOptimizer() override { } /** diff --git a/gtsam/nonlinear/NonlinearEquality.h b/gtsam/nonlinear/NonlinearEquality.h index 6286b73da..f4cf3cc88 100644 --- a/gtsam/nonlinear/NonlinearEquality.h +++ b/gtsam/nonlinear/NonlinearEquality.h @@ -77,7 +77,7 @@ public: NonlinearEquality() { } - virtual ~NonlinearEquality() { + ~NonlinearEquality() override { } /// @name Standard Constructors @@ -238,7 +238,7 @@ public: std::abs(mu)), key), value_(value) { } - virtual ~NonlinearEquality1() { + ~NonlinearEquality1() override { } /// @return a deep copy of this factor @@ -313,7 +313,7 @@ public: NonlinearEquality2(Key key1, Key key2, double mu = 1000.0) : Base(noiseModel::Constrained::All(traits::dimension, std::abs(mu)), key1, key2) { } - virtual ~NonlinearEquality2() { + ~NonlinearEquality2() override { } /// @return a deep copy of this factor diff --git a/gtsam/nonlinear/NonlinearFactor.h b/gtsam/nonlinear/NonlinearFactor.h index 00311fb87..8c257f7ca 100644 --- a/gtsam/nonlinear/NonlinearFactor.h +++ b/gtsam/nonlinear/NonlinearFactor.h @@ -169,7 +169,7 @@ public: NoiseModelFactor() {} /** Destructor */ - virtual ~NoiseModelFactor() {} + ~NoiseModelFactor() override {} /** * Constructor @@ -293,7 +293,7 @@ public: /** Default constructor for I/O only */ NoiseModelFactor1() {} - virtual ~NoiseModelFactor1() {} + ~NoiseModelFactor1() override {} inline Key key() const { return keys_[0]; } @@ -387,7 +387,7 @@ public: NoiseModelFactor2(const SharedNoiseModel& noiseModel, Key j1, Key j2) : Base(noiseModel, cref_list_of<2>(j1)(j2)) {} - virtual ~NoiseModelFactor2() {} + ~NoiseModelFactor2() override {} /** methods to retrieve both keys */ inline Key key1() const { return keys_[0]; } @@ -464,7 +464,7 @@ public: NoiseModelFactor3(const SharedNoiseModel& noiseModel, Key j1, Key j2, Key j3) : Base(noiseModel, cref_list_of<3>(j1)(j2)(j3)) {} - virtual ~NoiseModelFactor3() {} + ~NoiseModelFactor3() override {} /** methods to retrieve keys */ inline Key key1() const { return keys_[0]; } @@ -543,7 +543,7 @@ public: NoiseModelFactor4(const SharedNoiseModel& noiseModel, Key j1, Key j2, Key j3, Key j4) : Base(noiseModel, cref_list_of<4>(j1)(j2)(j3)(j4)) {} - virtual ~NoiseModelFactor4() {} + ~NoiseModelFactor4() override {} /** methods to retrieve keys */ inline Key key1() const { return keys_[0]; } @@ -626,7 +626,7 @@ public: NoiseModelFactor5(const SharedNoiseModel& noiseModel, Key j1, Key j2, Key j3, Key j4, Key j5) : Base(noiseModel, cref_list_of<5>(j1)(j2)(j3)(j4)(j5)) {} - virtual ~NoiseModelFactor5() {} + ~NoiseModelFactor5() override {} /** methods to retrieve keys */ inline Key key1() const { return keys_[0]; } @@ -713,7 +713,7 @@ public: NoiseModelFactor6(const SharedNoiseModel& noiseModel, Key j1, Key j2, Key j3, Key j4, Key j5, Key j6) : Base(noiseModel, cref_list_of<6>(j1)(j2)(j3)(j4)(j5)(j6)) {} - virtual ~NoiseModelFactor6() {} + ~NoiseModelFactor6() override {} /** methods to retrieve keys */ inline Key key1() const { return keys_[0]; } diff --git a/gtsam/nonlinear/PriorFactor.h b/gtsam/nonlinear/PriorFactor.h index 191a7eeaa..c745f7bd9 100644 --- a/gtsam/nonlinear/PriorFactor.h +++ b/gtsam/nonlinear/PriorFactor.h @@ -52,7 +52,7 @@ namespace gtsam { /** default constructor - only use for serialization */ PriorFactor() {} - virtual ~PriorFactor() {} + ~PriorFactor() override {} /** Constructor */ PriorFactor(Key key, const VALUE& prior, const SharedNoiseModel& model = nullptr) : diff --git a/gtsam/nonlinear/Values.h b/gtsam/nonlinear/Values.h index 120c8839c..893d5572f 100644 --- a/gtsam/nonlinear/Values.h +++ b/gtsam/nonlinear/Values.h @@ -442,7 +442,7 @@ namespace gtsam { ValuesKeyAlreadyExists(Key key) noexcept : key_(key) {} - virtual ~ValuesKeyAlreadyExists() noexcept {} + ~ValuesKeyAlreadyExists() noexcept override {} /// The duplicate key that was attempted to be added Key key() const noexcept { return key_; } @@ -465,7 +465,7 @@ namespace gtsam { ValuesKeyDoesNotExist(const char* operation, Key key) noexcept : operation_(operation), key_(key) {} - virtual ~ValuesKeyDoesNotExist() noexcept {} + ~ValuesKeyDoesNotExist() noexcept override {} /// The key that was attempted to be accessed that does not exist Key key() const noexcept { return key_; } @@ -490,7 +490,7 @@ namespace gtsam { const std::type_info& storedTypeId, const std::type_info& requestedTypeId) noexcept : key_(key), storedTypeId_(storedTypeId), requestedTypeId_(requestedTypeId) {} - virtual ~ValuesIncorrectType() noexcept {} + ~ValuesIncorrectType() noexcept override {} /// The key that was attempted to be accessed that does not exist Key key() const noexcept { return key_; } @@ -511,7 +511,7 @@ namespace gtsam { public: DynamicValuesMismatched() noexcept {} - virtual ~DynamicValuesMismatched() noexcept {} + ~DynamicValuesMismatched() noexcept override {} const char* what() const noexcept override { return "The Values 'this' and the argument passed to Values::localCoordinates have mismatched keys and values"; @@ -533,7 +533,7 @@ namespace gtsam { M1_(M1), N1_(N1), M2_(M2), N2_(N2) { } - virtual ~NoMatchFoundForFixed() noexcept { + ~NoMatchFoundForFixed() noexcept override { } GTSAM_EXPORT const char* what() const noexcept override; diff --git a/gtsam/nonlinear/WhiteNoiseFactor.h b/gtsam/nonlinear/WhiteNoiseFactor.h index 974998830..95f46ab6c 100644 --- a/gtsam/nonlinear/WhiteNoiseFactor.h +++ b/gtsam/nonlinear/WhiteNoiseFactor.h @@ -100,7 +100,7 @@ namespace gtsam { /// @{ /// Destructor - virtual ~WhiteNoiseFactor() { + ~WhiteNoiseFactor() override { } /// @} diff --git a/gtsam/nonlinear/internal/ExpressionNode.h b/gtsam/nonlinear/internal/ExpressionNode.h index ee3dc8929..2a1a07fb0 100644 --- a/gtsam/nonlinear/internal/ExpressionNode.h +++ b/gtsam/nonlinear/internal/ExpressionNode.h @@ -131,7 +131,7 @@ class ConstantExpression: public ExpressionNode { public: /// Destructor - virtual ~ConstantExpression() { + ~ConstantExpression() override { } /// Print @@ -172,7 +172,7 @@ class LeafExpression: public ExpressionNode { public: /// Destructor - virtual ~LeafExpression() { + ~LeafExpression() override { } /// Print @@ -244,7 +244,7 @@ class UnaryExpression: public ExpressionNode { public: /// Destructor - virtual ~UnaryExpression() { + ~UnaryExpression() override { } /// Print @@ -353,7 +353,7 @@ class BinaryExpression: public ExpressionNode { public: /// Destructor - virtual ~BinaryExpression() { + ~BinaryExpression() override { } /// Print @@ -460,7 +460,7 @@ class TernaryExpression: public ExpressionNode { public: /// Destructor - virtual ~TernaryExpression() { + ~TernaryExpression() override { } /// Print @@ -571,7 +571,7 @@ class ScalarMultiplyNode : public ExpressionNode { } /// Destructor - virtual ~ScalarMultiplyNode() {} + ~ScalarMultiplyNode() override {} /// Print void print(const std::string& indent = "") const override { @@ -659,7 +659,7 @@ class BinarySumNode : public ExpressionNode { } /// Destructor - virtual ~BinarySumNode() {} + ~BinarySumNode() override {} /// Print void print(const std::string& indent = "") const override { diff --git a/gtsam/nonlinear/tests/testCallRecord.cpp b/gtsam/nonlinear/tests/testCallRecord.cpp index 66c56e696..5d0d5d5f2 100644 --- a/gtsam/nonlinear/tests/testCallRecord.cpp +++ b/gtsam/nonlinear/tests/testCallRecord.cpp @@ -77,7 +77,7 @@ template<> struct traits : public Testable {}; struct Record: public internal::CallRecordImplementor { Record() : cc(0, 0) {} - virtual ~Record() { + ~Record() override { } void print(const std::string& indent) const { } diff --git a/gtsam/sam/BearingRangeFactor.h b/gtsam/sam/BearingRangeFactor.h index 482dbb974..da352f2e9 100644 --- a/gtsam/sam/BearingRangeFactor.h +++ b/gtsam/sam/BearingRangeFactor.h @@ -59,7 +59,7 @@ class BearingRangeFactor this->initialize(expression({{key1, key2}})); } - virtual ~BearingRangeFactor() {} + ~BearingRangeFactor() override {} /// @return a deep copy of this factor gtsam::NonlinearFactor::shared_ptr clone() const override { diff --git a/gtsam/sam/RangeFactor.h b/gtsam/sam/RangeFactor.h index d9890d2ef..2db659947 100644 --- a/gtsam/sam/RangeFactor.h +++ b/gtsam/sam/RangeFactor.h @@ -118,7 +118,7 @@ class RangeFactorWithTransform : public ExpressionFactorN { this->initialize(expression({key1, key2})); } - virtual ~RangeFactorWithTransform() {} + ~RangeFactorWithTransform() override {} /// @return a deep copy of this factor gtsam::NonlinearFactor::shared_ptr clone() const override { diff --git a/gtsam/sfm/ShonanGaugeFactor.h b/gtsam/sfm/ShonanGaugeFactor.h index 4847c5d58..d6240b1c4 100644 --- a/gtsam/sfm/ShonanGaugeFactor.h +++ b/gtsam/sfm/ShonanGaugeFactor.h @@ -90,7 +90,7 @@ public: } /// Destructor - virtual ~ShonanGaugeFactor() {} + ~ShonanGaugeFactor() override {} /// Calculate the error of the factor: always zero double error(const Values &c) const override { return 0; } diff --git a/gtsam/slam/AntiFactor.h b/gtsam/slam/AntiFactor.h index 277080b6b..3b559fe79 100644 --- a/gtsam/slam/AntiFactor.h +++ b/gtsam/slam/AntiFactor.h @@ -49,7 +49,7 @@ namespace gtsam { /** constructor - Creates the equivalent AntiFactor from an existing factor */ AntiFactor(NonlinearFactor::shared_ptr factor) : Base(factor->keys()), factor_(factor) {} - virtual ~AntiFactor() {} + ~AntiFactor() override {} /// @return a deep copy of this factor gtsam::NonlinearFactor::shared_ptr clone() const override { diff --git a/gtsam/slam/BetweenFactor.h b/gtsam/slam/BetweenFactor.h index a594e95d5..aef41d5fd 100644 --- a/gtsam/slam/BetweenFactor.h +++ b/gtsam/slam/BetweenFactor.h @@ -68,7 +68,7 @@ namespace gtsam { Base(model, key1, key2), measured_(measured) { } - virtual ~BetweenFactor() {} + ~BetweenFactor() override {} /// @return a deep copy of this factor gtsam::NonlinearFactor::shared_ptr clone() const override { diff --git a/gtsam/slam/BoundingConstraint.h b/gtsam/slam/BoundingConstraint.h index 43cc6d292..3d5842fa2 100644 --- a/gtsam/slam/BoundingConstraint.h +++ b/gtsam/slam/BoundingConstraint.h @@ -44,7 +44,7 @@ struct BoundingConstraint1: public NoiseModelFactor1 { threshold_(threshold), isGreaterThan_(isGreaterThan) { } - virtual ~BoundingConstraint1() {} + ~BoundingConstraint1() override {} inline double threshold() const { return threshold_; } inline bool isGreaterThan() const { return isGreaterThan_; } @@ -112,7 +112,7 @@ struct BoundingConstraint2: public NoiseModelFactor2 { : Base(noiseModel::Constrained::All(1, mu), key1, key2), threshold_(threshold), isGreaterThan_(isGreaterThan) {} - virtual ~BoundingConstraint2() {} + ~BoundingConstraint2() override {} inline double threshold() const { return threshold_; } inline bool isGreaterThan() const { return isGreaterThan_; } diff --git a/gtsam/slam/EssentialMatrixConstraint.h b/gtsam/slam/EssentialMatrixConstraint.h index d21ead31f..6274be963 100644 --- a/gtsam/slam/EssentialMatrixConstraint.h +++ b/gtsam/slam/EssentialMatrixConstraint.h @@ -57,7 +57,7 @@ public: Base(model, key1, key2), measuredE_(measuredE) { } - virtual ~EssentialMatrixConstraint() { + ~EssentialMatrixConstraint() override { } /// @return a deep copy of this factor diff --git a/gtsam/slam/GeneralSFMFactor.h b/gtsam/slam/GeneralSFMFactor.h index c9639d4d5..2e4543177 100644 --- a/gtsam/slam/GeneralSFMFactor.h +++ b/gtsam/slam/GeneralSFMFactor.h @@ -96,7 +96,7 @@ public: ///< constructor that takes doubles x,y to make a Point2 GeneralSFMFactor(double x, double y) : measured_(x, y) {} - virtual ~GeneralSFMFactor() {} ///< destructor + ~GeneralSFMFactor() override {} ///< destructor /// @return a deep copy of this factor gtsam::NonlinearFactor::shared_ptr clone() const override { @@ -230,7 +230,7 @@ public: Base(model, poseKey, landmarkKey, calibKey), measured_(measured) {} GeneralSFMFactor2():measured_(0.0,0.0) {} ///< default constructor - virtual ~GeneralSFMFactor2() {} ///< destructor + ~GeneralSFMFactor2() override {} ///< destructor /// @return a deep copy of this factor gtsam::NonlinearFactor::shared_ptr clone() const override { diff --git a/gtsam/slam/KarcherMeanFactor.h b/gtsam/slam/KarcherMeanFactor.h index b7cd3b11a..964cd598f 100644 --- a/gtsam/slam/KarcherMeanFactor.h +++ b/gtsam/slam/KarcherMeanFactor.h @@ -63,7 +63,7 @@ public: boost::optional beta = boost::none); /// Destructor - virtual ~KarcherMeanFactor() {} + ~KarcherMeanFactor() override {} /// Calculate the error of the factor: always zero double error(const Values &c) const override { return 0; } diff --git a/gtsam/slam/OrientedPlane3Factor.h b/gtsam/slam/OrientedPlane3Factor.h index e83464b1e..53c08511d 100644 --- a/gtsam/slam/OrientedPlane3Factor.h +++ b/gtsam/slam/OrientedPlane3Factor.h @@ -30,7 +30,7 @@ public: /// Constructor OrientedPlane3Factor() { } - virtual ~OrientedPlane3Factor() {} + ~OrientedPlane3Factor() override {} /// Constructor with measured plane coefficients (a,b,c,d), noise model, pose symbol OrientedPlane3Factor(const Vector&z, const SharedGaussian& noiseModel, diff --git a/gtsam/slam/PoseRotationPrior.h b/gtsam/slam/PoseRotationPrior.h index 7e8bdaa46..ba4d12a25 100644 --- a/gtsam/slam/PoseRotationPrior.h +++ b/gtsam/slam/PoseRotationPrior.h @@ -47,7 +47,7 @@ public: PoseRotationPrior(Key key, const POSE& pose_z, const SharedNoiseModel& model) : Base(model, key), measured_(pose_z.rotation()) {} - virtual ~PoseRotationPrior() {} + ~PoseRotationPrior() override {} /// @return a deep copy of this factor gtsam::NonlinearFactor::shared_ptr clone() const override { diff --git a/gtsam/slam/PoseTranslationPrior.h b/gtsam/slam/PoseTranslationPrior.h index 0c029c501..5bb3745e9 100644 --- a/gtsam/slam/PoseTranslationPrior.h +++ b/gtsam/slam/PoseTranslationPrior.h @@ -49,7 +49,7 @@ public: : Base(model, key), measured_(pose_z.translation()) { } - virtual ~PoseTranslationPrior() {} + ~PoseTranslationPrior() override {} const Translation& measured() const { return measured_; } diff --git a/gtsam/slam/ProjectionFactor.h b/gtsam/slam/ProjectionFactor.h index 266037469..67100a0ac 100644 --- a/gtsam/slam/ProjectionFactor.h +++ b/gtsam/slam/ProjectionFactor.h @@ -97,7 +97,7 @@ namespace gtsam { throwCheirality_(throwCheirality), verboseCheirality_(verboseCheirality) {} /** Virtual destructor */ - virtual ~GenericProjectionFactor() {} + ~GenericProjectionFactor() override {} /// @return a deep copy of this factor gtsam::NonlinearFactor::shared_ptr clone() const override { diff --git a/gtsam/slam/ReferenceFrameFactor.h b/gtsam/slam/ReferenceFrameFactor.h index e41b5f908..40c8e29b7 100644 --- a/gtsam/slam/ReferenceFrameFactor.h +++ b/gtsam/slam/ReferenceFrameFactor.h @@ -87,7 +87,7 @@ public: : Base(noiseModel::Isotropic::Sigma(traits::dimension, sigma), globalKey, transKey, localKey) {} - virtual ~ReferenceFrameFactor(){} + ~ReferenceFrameFactor() override{} NonlinearFactor::shared_ptr clone() const override { return boost::static_pointer_cast( diff --git a/gtsam/slam/RegularImplicitSchurFactor.h b/gtsam/slam/RegularImplicitSchurFactor.h index 71474a8ab..2ed6aa491 100644 --- a/gtsam/slam/RegularImplicitSchurFactor.h +++ b/gtsam/slam/RegularImplicitSchurFactor.h @@ -59,7 +59,7 @@ public: } /// Destructor - virtual ~RegularImplicitSchurFactor() { + ~RegularImplicitSchurFactor() override { } std::vector >& FBlocks() const { diff --git a/gtsam/slam/SmartFactorBase.h b/gtsam/slam/SmartFactorBase.h index 85f9e7c3f..0b0308c5c 100644 --- a/gtsam/slam/SmartFactorBase.h +++ b/gtsam/slam/SmartFactorBase.h @@ -112,7 +112,7 @@ protected: } /// Virtual destructor, subclasses from NonlinearFactor - virtual ~SmartFactorBase() { + ~SmartFactorBase() override { } /** diff --git a/gtsam/slam/SmartProjectionFactor.h b/gtsam/slam/SmartProjectionFactor.h index bc01f5d85..475a9e829 100644 --- a/gtsam/slam/SmartProjectionFactor.h +++ b/gtsam/slam/SmartProjectionFactor.h @@ -90,7 +90,7 @@ public: result_(TriangulationResult::Degenerate()) {} /** Virtual destructor */ - virtual ~SmartProjectionFactor() { + ~SmartProjectionFactor() override { } /** diff --git a/gtsam/slam/SmartProjectionPoseFactor.h b/gtsam/slam/SmartProjectionPoseFactor.h index cccdf20d6..c7b1d5424 100644 --- a/gtsam/slam/SmartProjectionPoseFactor.h +++ b/gtsam/slam/SmartProjectionPoseFactor.h @@ -94,7 +94,7 @@ public: } /** Virtual destructor */ - virtual ~SmartProjectionPoseFactor() { + ~SmartProjectionPoseFactor() override { } /** diff --git a/gtsam/slam/StereoFactor.h b/gtsam/slam/StereoFactor.h index 6556723bd..de084c762 100644 --- a/gtsam/slam/StereoFactor.h +++ b/gtsam/slam/StereoFactor.h @@ -88,7 +88,7 @@ public: throwCheirality_(throwCheirality), verboseCheirality_(verboseCheirality) {} /** Virtual destructor */ - virtual ~GenericStereoFactor() {} + ~GenericStereoFactor() override {} /// @return a deep copy of this factor gtsam::NonlinearFactor::shared_ptr clone() const override { diff --git a/gtsam/slam/TriangulationFactor.h b/gtsam/slam/TriangulationFactor.h index 9d02ad321..f12053d29 100644 --- a/gtsam/slam/TriangulationFactor.h +++ b/gtsam/slam/TriangulationFactor.h @@ -86,7 +86,7 @@ public: } /** Virtual destructor */ - virtual ~TriangulationFactor() { + ~TriangulationFactor() override { } /// @return a deep copy of this factor diff --git a/gtsam/symbolic/SymbolicConditional.h b/gtsam/symbolic/SymbolicConditional.h index 9163cdba6..ead72a989 100644 --- a/gtsam/symbolic/SymbolicConditional.h +++ b/gtsam/symbolic/SymbolicConditional.h @@ -95,7 +95,7 @@ namespace gtsam { return FromIteratorsShared(keys.begin(), keys.end(), nrFrontals); } - virtual ~SymbolicConditional() {} + ~SymbolicConditional() override {} /// Copy this object as its actual derived type. SymbolicFactor::shared_ptr clone() const { return boost::make_shared(*this); } diff --git a/gtsam_unstable/discrete/Constraint.h b/gtsam_unstable/discrete/Constraint.h index 136704c2d..c3a26de68 100644 --- a/gtsam_unstable/discrete/Constraint.h +++ b/gtsam_unstable/discrete/Constraint.h @@ -67,7 +67,7 @@ namespace gtsam { Constraint(); /// Virtual destructor - virtual ~Constraint() {} + ~Constraint() override {} /// @} /// @name Standard Interface diff --git a/gtsam_unstable/dynamics/FullIMUFactor.h b/gtsam_unstable/dynamics/FullIMUFactor.h index c8c351d7a..531d54af1 100644 --- a/gtsam_unstable/dynamics/FullIMUFactor.h +++ b/gtsam_unstable/dynamics/FullIMUFactor.h @@ -48,7 +48,7 @@ public: assert(model->dim() == 9); } - virtual ~FullIMUFactor() {} + ~FullIMUFactor() override {} /// @return a deep copy of this factor gtsam::NonlinearFactor::shared_ptr clone() const override { diff --git a/gtsam_unstable/dynamics/IMUFactor.h b/gtsam_unstable/dynamics/IMUFactor.h index fb864a78d..62a6abcd9 100644 --- a/gtsam_unstable/dynamics/IMUFactor.h +++ b/gtsam_unstable/dynamics/IMUFactor.h @@ -41,7 +41,7 @@ public: double dt, const Key& key1, const Key& key2, const SharedNoiseModel& model) : Base(model, key1, key2), accel_(imu_vector.head(3)), gyro_(imu_vector.tail(3)), dt_(dt) {} - virtual ~IMUFactor() {} + ~IMUFactor() override {} /// @return a deep copy of this factor gtsam::NonlinearFactor::shared_ptr clone() const override { diff --git a/gtsam_unstable/dynamics/SimpleHelicopter.h b/gtsam_unstable/dynamics/SimpleHelicopter.h index 42ef04f84..976f448c5 100644 --- a/gtsam_unstable/dynamics/SimpleHelicopter.h +++ b/gtsam_unstable/dynamics/SimpleHelicopter.h @@ -33,7 +33,7 @@ public: Base(noiseModel::Constrained::All(6, std::abs(mu)), gKey1, gKey, xiKey), h_(h) { } - virtual ~Reconstruction() {} + ~Reconstruction() override {} /// @return a deep copy of this factor gtsam::NonlinearFactor::shared_ptr clone() const override { @@ -95,7 +95,7 @@ public: Base(noiseModel::Constrained::All(6, std::abs(mu)), xiKey1, xiKey_1, gKey), h_(h), Inertia_(Inertia), Fu_(Fu), m_(m) { } - virtual ~DiscreteEulerPoincareHelicopter() {} + ~DiscreteEulerPoincareHelicopter() override {} /// @return a deep copy of this factor gtsam::NonlinearFactor::shared_ptr clone() const override { diff --git a/gtsam_unstable/dynamics/VelocityConstraint.h b/gtsam_unstable/dynamics/VelocityConstraint.h index 986d8e271..56171a728 100644 --- a/gtsam_unstable/dynamics/VelocityConstraint.h +++ b/gtsam_unstable/dynamics/VelocityConstraint.h @@ -70,7 +70,7 @@ public: VelocityConstraint(Key key1, Key key2, double dt, const gtsam::SharedNoiseModel& model) : Base(model, key1, key2), dt_(dt), integration_mode_(dynamics::TRAPEZOIDAL) {} - virtual ~VelocityConstraint() {} + ~VelocityConstraint() override {} /// @return a deep copy of this factor gtsam::NonlinearFactor::shared_ptr clone() const override { diff --git a/gtsam_unstable/dynamics/VelocityConstraint3.h b/gtsam_unstable/dynamics/VelocityConstraint3.h index f6cd8ccc4..c9f05cf98 100644 --- a/gtsam_unstable/dynamics/VelocityConstraint3.h +++ b/gtsam_unstable/dynamics/VelocityConstraint3.h @@ -28,7 +28,7 @@ public: ///TODO: comment VelocityConstraint3(Key key1, Key key2, Key velKey, double dt, double mu = 1000.0) : Base(noiseModel::Constrained::All(1, std::abs(mu)), key1, key2, velKey), dt_(dt) {} - virtual ~VelocityConstraint3() {} + ~VelocityConstraint3() override {} /// @return a deep copy of this factor gtsam::NonlinearFactor::shared_ptr clone() const override { diff --git a/gtsam_unstable/linear/InfeasibleInitialValues.h b/gtsam_unstable/linear/InfeasibleInitialValues.h index 6f589d0c3..dbd1b3940 100644 --- a/gtsam_unstable/linear/InfeasibleInitialValues.h +++ b/gtsam_unstable/linear/InfeasibleInitialValues.h @@ -29,7 +29,7 @@ public: InfeasibleInitialValues() { } - virtual ~InfeasibleInitialValues() noexcept { + ~InfeasibleInitialValues() noexcept override { } const char *what() const noexcept override { diff --git a/gtsam_unstable/linear/InfeasibleOrUnboundedProblem.h b/gtsam_unstable/linear/InfeasibleOrUnboundedProblem.h index 25742d61f..5f9b9f5b3 100644 --- a/gtsam_unstable/linear/InfeasibleOrUnboundedProblem.h +++ b/gtsam_unstable/linear/InfeasibleOrUnboundedProblem.h @@ -25,7 +25,7 @@ class InfeasibleOrUnboundedProblem: public ThreadsafeException< public: InfeasibleOrUnboundedProblem() { } - virtual ~InfeasibleOrUnboundedProblem() noexcept { + ~InfeasibleOrUnboundedProblem() noexcept override { } const char* what() const noexcept override { diff --git a/gtsam_unstable/linear/LinearCost.h b/gtsam_unstable/linear/LinearCost.h index c22c389be..9ac7e16af 100644 --- a/gtsam_unstable/linear/LinearCost.h +++ b/gtsam_unstable/linear/LinearCost.h @@ -84,7 +84,7 @@ public: } /** Virtual destructor */ - virtual ~LinearCost() { + ~LinearCost() override { } /** equals */ diff --git a/gtsam_unstable/linear/LinearEquality.h b/gtsam_unstable/linear/LinearEquality.h index d960d8336..d2c8586f2 100644 --- a/gtsam_unstable/linear/LinearEquality.h +++ b/gtsam_unstable/linear/LinearEquality.h @@ -85,7 +85,7 @@ public: } /** Virtual destructor */ - virtual ~LinearEquality() { + ~LinearEquality() override { } /** equals */ diff --git a/gtsam_unstable/linear/LinearInequality.h b/gtsam_unstable/linear/LinearInequality.h index d353afc46..dbb9004ea 100644 --- a/gtsam_unstable/linear/LinearInequality.h +++ b/gtsam_unstable/linear/LinearInequality.h @@ -96,7 +96,7 @@ public: } /** Virtual destructor */ - virtual ~LinearInequality() { + ~LinearInequality() override { } /** equals */ diff --git a/gtsam_unstable/linear/QPSParserException.h b/gtsam_unstable/linear/QPSParserException.h index ef14ed430..aaa74ad56 100644 --- a/gtsam_unstable/linear/QPSParserException.h +++ b/gtsam_unstable/linear/QPSParserException.h @@ -25,7 +25,7 @@ public: QPSParserException() { } - virtual ~QPSParserException() noexcept { + ~QPSParserException() noexcept override { } const char *what() const noexcept override { diff --git a/gtsam_unstable/nonlinear/BatchFixedLagSmoother.h b/gtsam_unstable/nonlinear/BatchFixedLagSmoother.h index b4645e4ed..94cf130cf 100644 --- a/gtsam_unstable/nonlinear/BatchFixedLagSmoother.h +++ b/gtsam_unstable/nonlinear/BatchFixedLagSmoother.h @@ -38,7 +38,7 @@ public: FixedLagSmoother(smootherLag), parameters_(parameters), enforceConsistency_(enforceConsistency) { }; /** destructor */ - virtual ~BatchFixedLagSmoother() { }; + ~BatchFixedLagSmoother() override { }; /** Print the factor for debugging and testing (implementing Testable) */ void print(const std::string& s = "BatchFixedLagSmoother:\n", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override; diff --git a/gtsam_unstable/nonlinear/ConcurrentBatchFilter.h b/gtsam_unstable/nonlinear/ConcurrentBatchFilter.h index c99c67492..7e35476b9 100644 --- a/gtsam_unstable/nonlinear/ConcurrentBatchFilter.h +++ b/gtsam_unstable/nonlinear/ConcurrentBatchFilter.h @@ -64,7 +64,7 @@ public: ConcurrentBatchFilter(const LevenbergMarquardtParams& parameters = LevenbergMarquardtParams()) : parameters_(parameters) {}; /** Default destructor */ - virtual ~ConcurrentBatchFilter() {}; + ~ConcurrentBatchFilter() override {}; /** Implement a GTSAM standard 'print' function */ void print(const std::string& s = "Concurrent Batch Filter:\n", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override; @@ -130,7 +130,7 @@ public: * Perform any required operations before the synchronization process starts. * Called by 'synchronize' */ - virtual void presync() override; + void presync() override; /** * Populate the provided containers with factors that constitute the filter branch summarization @@ -162,7 +162,7 @@ public: * Perform any required operations after the synchronization process finishes. * Called by 'synchronize' */ - virtual void postsync() override; + void postsync() override; protected: diff --git a/gtsam_unstable/nonlinear/ConcurrentBatchSmoother.h b/gtsam_unstable/nonlinear/ConcurrentBatchSmoother.h index 364d02caf..51d3284a4 100644 --- a/gtsam_unstable/nonlinear/ConcurrentBatchSmoother.h +++ b/gtsam_unstable/nonlinear/ConcurrentBatchSmoother.h @@ -57,7 +57,7 @@ public: ConcurrentBatchSmoother(const LevenbergMarquardtParams& parameters = LevenbergMarquardtParams()) : parameters_(parameters) {}; /** Default destructor */ - virtual ~ConcurrentBatchSmoother() {}; + ~ConcurrentBatchSmoother() override {}; /** Implement a GTSAM standard 'print' function */ void print(const std::string& s = "Concurrent Batch Smoother:\n", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override; @@ -124,7 +124,7 @@ public: * Perform any required operations before the synchronization process starts. * Called by 'synchronize' */ - virtual void presync() override; + void presync() override; /** * Populate the provided containers with factors that constitute the smoother branch summarization @@ -150,7 +150,7 @@ public: * Perform any required operations after the synchronization process finishes. * Called by 'synchronize' */ - virtual void postsync() override; + void postsync() override; protected: diff --git a/gtsam_unstable/nonlinear/ConcurrentIncrementalFilter.h b/gtsam_unstable/nonlinear/ConcurrentIncrementalFilter.h index d0525a4da..eb1174749 100644 --- a/gtsam_unstable/nonlinear/ConcurrentIncrementalFilter.h +++ b/gtsam_unstable/nonlinear/ConcurrentIncrementalFilter.h @@ -64,7 +64,7 @@ public: ConcurrentIncrementalFilter(const ISAM2Params& parameters = ISAM2Params()) : isam2_(parameters) {}; /** Default destructor */ - virtual ~ConcurrentIncrementalFilter() {}; + ~ConcurrentIncrementalFilter() override {}; /** Implement a GTSAM standard 'print' function */ void print(const std::string& s = "Concurrent Incremental Filter:\n", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override; diff --git a/gtsam_unstable/nonlinear/ConcurrentIncrementalSmoother.h b/gtsam_unstable/nonlinear/ConcurrentIncrementalSmoother.h index 8848b6a43..a27751561 100644 --- a/gtsam_unstable/nonlinear/ConcurrentIncrementalSmoother.h +++ b/gtsam_unstable/nonlinear/ConcurrentIncrementalSmoother.h @@ -54,7 +54,7 @@ public: ConcurrentIncrementalSmoother(const ISAM2Params& parameters = ISAM2Params()) : isam2_(parameters) {}; /** Default destructor */ - virtual ~ConcurrentIncrementalSmoother() {}; + ~ConcurrentIncrementalSmoother() override {}; /** Implement a GTSAM standard 'print' function */ void print(const std::string& s = "Concurrent Incremental Smoother:\n", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override; diff --git a/gtsam_unstable/nonlinear/IncrementalFixedLagSmoother.h b/gtsam_unstable/nonlinear/IncrementalFixedLagSmoother.h index 3cf6c16d3..79c05a01a 100644 --- a/gtsam_unstable/nonlinear/IncrementalFixedLagSmoother.h +++ b/gtsam_unstable/nonlinear/IncrementalFixedLagSmoother.h @@ -44,15 +44,15 @@ public: } /** destructor */ - virtual ~IncrementalFixedLagSmoother() { + ~IncrementalFixedLagSmoother() override { } /** Print the factor for debugging and testing (implementing Testable) */ - virtual void print(const std::string& s = "IncrementalFixedLagSmoother:\n", + void print(const std::string& s = "IncrementalFixedLagSmoother:\n", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override; /** Check if two IncrementalFixedLagSmoother Objects are equal */ - virtual bool equals(const FixedLagSmoother& rhs, double tol = 1e-9) const override; + bool equals(const FixedLagSmoother& rhs, double tol = 1e-9) const override; /** * Add new factors, updating the solution and re-linearizing as needed. diff --git a/gtsam_unstable/nonlinear/LinearizedFactor.h b/gtsam_unstable/nonlinear/LinearizedFactor.h index caf67de21..1ae8a7906 100644 --- a/gtsam_unstable/nonlinear/LinearizedFactor.h +++ b/gtsam_unstable/nonlinear/LinearizedFactor.h @@ -53,7 +53,7 @@ public: */ LinearizedGaussianFactor(const GaussianFactor::shared_ptr& gaussian, const Values& lin_points); - virtual ~LinearizedGaussianFactor() {}; + ~LinearizedGaussianFactor() override {}; // access functions const Values& linearizationPoint() const { return lin_points_; } @@ -109,7 +109,7 @@ public: */ LinearizedJacobianFactor(const JacobianFactor::shared_ptr& jacobian, const Values& lin_points); - virtual ~LinearizedJacobianFactor() {} + ~LinearizedJacobianFactor() override {} /// @return a deep copy of this factor gtsam::NonlinearFactor::shared_ptr clone() const override { @@ -199,7 +199,7 @@ public: */ LinearizedHessianFactor(const HessianFactor::shared_ptr& hessian, const Values& lin_points); - virtual ~LinearizedHessianFactor() {} + ~LinearizedHessianFactor() override {} /// @return a deep copy of this factor gtsam::NonlinearFactor::shared_ptr clone() const override { diff --git a/gtsam_unstable/slam/BetweenFactorEM.h b/gtsam_unstable/slam/BetweenFactorEM.h index 43607ac41..98ec59fe9 100644 --- a/gtsam_unstable/slam/BetweenFactorEM.h +++ b/gtsam_unstable/slam/BetweenFactorEM.h @@ -78,7 +78,7 @@ public: flag_bump_up_near_zero_probs) { } - virtual ~BetweenFactorEM() { + ~BetweenFactorEM() override { } /** implement functions needed for Testable */ diff --git a/gtsam_unstable/slam/BiasedGPSFactor.h b/gtsam_unstable/slam/BiasedGPSFactor.h index c8bbdd78a..f2e9d3fa8 100644 --- a/gtsam_unstable/slam/BiasedGPSFactor.h +++ b/gtsam_unstable/slam/BiasedGPSFactor.h @@ -50,7 +50,7 @@ namespace gtsam { Base(model, posekey, biaskey), measured_(measured) { } - virtual ~BiasedGPSFactor() {} + ~BiasedGPSFactor() override {} /** implement functions needed for Testable */ diff --git a/gtsam_unstable/slam/DummyFactor.h b/gtsam_unstable/slam/DummyFactor.h index 08b1c800a..0484fc4c3 100644 --- a/gtsam_unstable/slam/DummyFactor.h +++ b/gtsam_unstable/slam/DummyFactor.h @@ -29,7 +29,7 @@ public: /** standard binary constructor */ DummyFactor(const Key& key1, size_t dim1, const Key& key2, size_t dim2); - virtual ~DummyFactor() {} + ~DummyFactor() override {} // testable diff --git a/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel.h b/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel.h index 745605325..165135114 100644 --- a/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel.h +++ b/gtsam_unstable/slam/EquivInertialNavFactor_GlobalVel.h @@ -128,7 +128,7 @@ public: dt12_(dt12), world_g_(world_g), world_rho_(world_rho), world_omega_earth_(world_omega_earth), Jacobian_wrt_t0_Overall_(Jacobian_wrt_t0_Overall), Bias_initial_(Bias_initial), body_P_sensor_(body_P_sensor) { } - virtual ~EquivInertialNavFactor_GlobalVel() {} + ~EquivInertialNavFactor_GlobalVel() override {} /** implement functions needed for Testable */ diff --git a/gtsam_unstable/slam/GaussMarkov1stOrderFactor.h b/gtsam_unstable/slam/GaussMarkov1stOrderFactor.h index f6de48625..52e4f44cb 100644 --- a/gtsam_unstable/slam/GaussMarkov1stOrderFactor.h +++ b/gtsam_unstable/slam/GaussMarkov1stOrderFactor.h @@ -66,7 +66,7 @@ public: Base(calcDiscreteNoiseModel(model, delta_t), key1, key2), dt_(delta_t), tau_(tau) { } - virtual ~GaussMarkov1stOrderFactor() {} + ~GaussMarkov1stOrderFactor() override {} /** implement functions needed for Testable */ diff --git a/gtsam_unstable/slam/InertialNavFactor_GlobalVelocity.h b/gtsam_unstable/slam/InertialNavFactor_GlobalVelocity.h index e5a3e9118..f031f4884 100644 --- a/gtsam_unstable/slam/InertialNavFactor_GlobalVelocity.h +++ b/gtsam_unstable/slam/InertialNavFactor_GlobalVelocity.h @@ -109,7 +109,7 @@ public: Pose1, Vel1, IMUBias1, Pose2, Vel2), measurement_acc_(measurement_acc), measurement_gyro_(measurement_gyro), dt_(measurement_dt), world_g_(world_g), world_rho_(world_rho), world_omega_earth_(world_omega_earth), body_P_sensor_(body_P_sensor) { } - virtual ~InertialNavFactor_GlobalVelocity() {} + ~InertialNavFactor_GlobalVelocity() override {} /** implement functions needed for Testable */ diff --git a/gtsam_unstable/slam/InvDepthFactor3.h b/gtsam_unstable/slam/InvDepthFactor3.h index 50b0c5980..3fd86f271 100644 --- a/gtsam_unstable/slam/InvDepthFactor3.h +++ b/gtsam_unstable/slam/InvDepthFactor3.h @@ -62,7 +62,7 @@ public: Base(model, poseKey, pointKey, invDepthKey), measured_(measured), K_(K) {} /** Virtual destructor */ - virtual ~InvDepthFactor3() {} + ~InvDepthFactor3() override {} /** * print diff --git a/gtsam_unstable/slam/InvDepthFactorVariant1.h b/gtsam_unstable/slam/InvDepthFactorVariant1.h index 785556750..7a34ab1bc 100644 --- a/gtsam_unstable/slam/InvDepthFactorVariant1.h +++ b/gtsam_unstable/slam/InvDepthFactorVariant1.h @@ -58,7 +58,7 @@ public: Base(model, poseKey, landmarkKey), measured_(measured), K_(K) {} /** Virtual destructor */ - virtual ~InvDepthFactorVariant1() {} + ~InvDepthFactorVariant1() override {} /** * print diff --git a/gtsam_unstable/slam/InvDepthFactorVariant2.h b/gtsam_unstable/slam/InvDepthFactorVariant2.h index 97ceb8a8b..0462aefad 100644 --- a/gtsam_unstable/slam/InvDepthFactorVariant2.h +++ b/gtsam_unstable/slam/InvDepthFactorVariant2.h @@ -61,7 +61,7 @@ public: Base(model, poseKey, landmarkKey), measured_(measured), K_(K), referencePoint_(referencePoint) {} /** Virtual destructor */ - virtual ~InvDepthFactorVariant2() {} + ~InvDepthFactorVariant2() override {} /** * print diff --git a/gtsam_unstable/slam/InvDepthFactorVariant3.h b/gtsam_unstable/slam/InvDepthFactorVariant3.h index 21c7aa6de..454358a0e 100644 --- a/gtsam_unstable/slam/InvDepthFactorVariant3.h +++ b/gtsam_unstable/slam/InvDepthFactorVariant3.h @@ -60,7 +60,7 @@ public: Base(model, poseKey, landmarkKey), measured_(measured), K_(K) {} /** Virtual destructor */ - virtual ~InvDepthFactorVariant3a() {} + ~InvDepthFactorVariant3a() override {} /** * print @@ -180,7 +180,7 @@ public: Base(model, poseKey1, poseKey2, landmarkKey), measured_(measured), K_(K) {} /** Virtual destructor */ - virtual ~InvDepthFactorVariant3b() {} + ~InvDepthFactorVariant3b() override {} /** * print diff --git a/gtsam_unstable/slam/MultiProjectionFactor.h b/gtsam_unstable/slam/MultiProjectionFactor.h index b6bf2a9c7..afc9e0b18 100644 --- a/gtsam_unstable/slam/MultiProjectionFactor.h +++ b/gtsam_unstable/slam/MultiProjectionFactor.h @@ -98,7 +98,7 @@ namespace gtsam { throwCheirality_(throwCheirality), verboseCheirality_(verboseCheirality) {} /** Virtual destructor */ - virtual ~MultiProjectionFactor() {} + ~MultiProjectionFactor() override {} /// @return a deep copy of this factor NonlinearFactor::shared_ptr clone() const override { diff --git a/gtsam_unstable/slam/PartialPriorFactor.h b/gtsam_unstable/slam/PartialPriorFactor.h index d284366e8..c1984992b 100644 --- a/gtsam_unstable/slam/PartialPriorFactor.h +++ b/gtsam_unstable/slam/PartialPriorFactor.h @@ -66,7 +66,7 @@ namespace gtsam { public: - virtual ~PartialPriorFactor() {} + ~PartialPriorFactor() override {} /** Single Element Constructor: acts on a single parameter specified by idx */ PartialPriorFactor(Key key, size_t idx, double prior, const SharedNoiseModel& model) : diff --git a/gtsam_unstable/slam/PoseBetweenFactor.h b/gtsam_unstable/slam/PoseBetweenFactor.h index e20792e25..a6c583418 100644 --- a/gtsam_unstable/slam/PoseBetweenFactor.h +++ b/gtsam_unstable/slam/PoseBetweenFactor.h @@ -56,7 +56,7 @@ namespace gtsam { Base(model, key1, key2), measured_(measured), body_P_sensor_(body_P_sensor) { } - virtual ~PoseBetweenFactor() {} + ~PoseBetweenFactor() override {} /// @return a deep copy of this factor gtsam::NonlinearFactor::shared_ptr clone() const override { diff --git a/gtsam_unstable/slam/PosePriorFactor.h b/gtsam_unstable/slam/PosePriorFactor.h index c9965f9bf..f657fc443 100644 --- a/gtsam_unstable/slam/PosePriorFactor.h +++ b/gtsam_unstable/slam/PosePriorFactor.h @@ -47,7 +47,7 @@ namespace gtsam { /** default constructor - only use for serialization */ PosePriorFactor() {} - virtual ~PosePriorFactor() {} + ~PosePriorFactor() override {} /** Constructor */ PosePriorFactor(Key key, const POSE& prior, const SharedNoiseModel& model, diff --git a/gtsam_unstable/slam/ProjectionFactorPPP.h b/gtsam_unstable/slam/ProjectionFactorPPP.h index caa388e2f..84adda707 100644 --- a/gtsam_unstable/slam/ProjectionFactorPPP.h +++ b/gtsam_unstable/slam/ProjectionFactorPPP.h @@ -93,7 +93,7 @@ namespace gtsam { throwCheirality_(throwCheirality), verboseCheirality_(verboseCheirality) {} /** Virtual destructor */ - virtual ~ProjectionFactorPPP() {} + ~ProjectionFactorPPP() override {} /// @return a deep copy of this factor NonlinearFactor::shared_ptr clone() const override { diff --git a/gtsam_unstable/slam/ProjectionFactorPPPC.h b/gtsam_unstable/slam/ProjectionFactorPPPC.h index af3294bce..fbc11503c 100644 --- a/gtsam_unstable/slam/ProjectionFactorPPPC.h +++ b/gtsam_unstable/slam/ProjectionFactorPPPC.h @@ -88,7 +88,7 @@ namespace gtsam { throwCheirality_(throwCheirality), verboseCheirality_(verboseCheirality) {} /** Virtual destructor */ - virtual ~ProjectionFactorPPPC() {} + ~ProjectionFactorPPPC() override {} /// @return a deep copy of this factor NonlinearFactor::shared_ptr clone() const override { diff --git a/gtsam_unstable/slam/RelativeElevationFactor.h b/gtsam_unstable/slam/RelativeElevationFactor.h index b713d45dc..ebf91d1f7 100644 --- a/gtsam_unstable/slam/RelativeElevationFactor.h +++ b/gtsam_unstable/slam/RelativeElevationFactor.h @@ -40,7 +40,7 @@ public: RelativeElevationFactor(Key poseKey, Key pointKey, double measured, const SharedNoiseModel& model); - virtual ~RelativeElevationFactor() {} + ~RelativeElevationFactor() override {} /// @return a deep copy of this factor gtsam::NonlinearFactor::shared_ptr clone() const override { diff --git a/gtsam_unstable/slam/SmartRangeFactor.h b/gtsam_unstable/slam/SmartRangeFactor.h index 6bab3f334..14e97f6bc 100644 --- a/gtsam_unstable/slam/SmartRangeFactor.h +++ b/gtsam_unstable/slam/SmartRangeFactor.h @@ -54,7 +54,7 @@ class SmartRangeFactor: public NoiseModelFactor { NoiseModelFactor(noiseModel::Isotropic::Sigma(1, s)), variance_(s * s) { } - virtual ~SmartRangeFactor() { + ~SmartRangeFactor() override { } /// Add a range measurement to a pose with given key. diff --git a/gtsam_unstable/slam/SmartStereoProjectionFactor.h b/gtsam_unstable/slam/SmartStereoProjectionFactor.h index ac063eff9..5010de8fd 100644 --- a/gtsam_unstable/slam/SmartStereoProjectionFactor.h +++ b/gtsam_unstable/slam/SmartStereoProjectionFactor.h @@ -93,7 +93,7 @@ public: } /** Virtual destructor */ - virtual ~SmartStereoProjectionFactor() { + ~SmartStereoProjectionFactor() override { } /** diff --git a/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h b/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h index 926a49de7..2a8180ac5 100644 --- a/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h +++ b/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h @@ -71,7 +71,7 @@ class SmartStereoProjectionPoseFactor : public SmartStereoProjectionFactor { const boost::optional& body_P_sensor = boost::none); /** Virtual destructor */ - virtual ~SmartStereoProjectionPoseFactor() = default; + ~SmartStereoProjectionPoseFactor() override = default; /** * add a new measurement and pose key diff --git a/gtsam_unstable/slam/TransformBtwRobotsUnaryFactor.h b/gtsam_unstable/slam/TransformBtwRobotsUnaryFactor.h index a17e07f9c..956c75999 100644 --- a/gtsam_unstable/slam/TransformBtwRobotsUnaryFactor.h +++ b/gtsam_unstable/slam/TransformBtwRobotsUnaryFactor.h @@ -77,7 +77,7 @@ namespace gtsam { } - virtual ~TransformBtwRobotsUnaryFactor() {} + ~TransformBtwRobotsUnaryFactor() override {} /** Clone */ diff --git a/gtsam_unstable/slam/TransformBtwRobotsUnaryFactorEM.h b/gtsam_unstable/slam/TransformBtwRobotsUnaryFactorEM.h index 8a56a5d02..2b2edfae9 100644 --- a/gtsam_unstable/slam/TransformBtwRobotsUnaryFactorEM.h +++ b/gtsam_unstable/slam/TransformBtwRobotsUnaryFactorEM.h @@ -93,7 +93,7 @@ namespace gtsam { } - virtual ~TransformBtwRobotsUnaryFactorEM() {} + ~TransformBtwRobotsUnaryFactorEM() override {} /** Clone */ diff --git a/tests/ImuMeasurement.h b/tests/ImuMeasurement.h index d49759545..c2c7851d1 100644 --- a/tests/ImuMeasurement.h +++ b/tests/ImuMeasurement.h @@ -18,7 +18,7 @@ class ImuMeasurement : public Measurement { ImuMeasurement() : Measurement("ImuMeasurement"), I_a_WI{0, 0, 0}, I_w_WI{0, 0, 0} {} - virtual ~ImuMeasurement() override {} + ~ImuMeasurement() override {} friend std::ostream& operator<<(std::ostream& stream, const ImuMeasurement& meas); diff --git a/tests/simulated2D.h b/tests/simulated2D.h index ed412bba8..097dbd3fe 100644 --- a/tests/simulated2D.h +++ b/tests/simulated2D.h @@ -143,7 +143,7 @@ namespace simulated2D { return (prior(x, H) - measured_); } - virtual ~GenericPrior() {} + ~GenericPrior() override {} /// @return a deep copy of this factor gtsam::NonlinearFactor::shared_ptr clone() const override { @@ -189,7 +189,7 @@ namespace simulated2D { return (odo(x1, x2, H1, H2) - measured_); } - virtual ~GenericOdometry() {} + ~GenericOdometry() override {} /// @return a deep copy of this factor gtsam::NonlinearFactor::shared_ptr clone() const override { @@ -236,7 +236,7 @@ namespace simulated2D { return (mea(x1, x2, H1, H2) - measured_); } - virtual ~GenericMeasurement() {} + ~GenericMeasurement() override {} /// @return a deep copy of this factor gtsam::NonlinearFactor::shared_ptr clone() const override { diff --git a/tests/simulated2DConstraints.h b/tests/simulated2DConstraints.h index cb8c09fc8..1609876b6 100644 --- a/tests/simulated2DConstraints.h +++ b/tests/simulated2DConstraints.h @@ -57,7 +57,7 @@ namespace simulated2D { typedef boost::shared_ptr > shared_ptr; ///< boost::shared_ptr convenience typedef typedef VALUE Point; ///< Constrained variable type - virtual ~ScalarCoordConstraint1() {} + ~ScalarCoordConstraint1() override {} /// @return a deep copy of this factor gtsam::NonlinearFactor::shared_ptr clone() const override { @@ -125,7 +125,7 @@ namespace simulated2D { typedef MaxDistanceConstraint This; ///< This class for factor typedef VALUE Point; ///< Type of variable constrained - virtual ~MaxDistanceConstraint() {} + ~MaxDistanceConstraint() override {} /// @return a deep copy of this factor gtsam::NonlinearFactor::shared_ptr clone() const override { @@ -174,7 +174,7 @@ namespace simulated2D { typedef POSE Pose; ///< Type of pose variable constrained typedef POINT Point; ///< Type of point variable constrained - virtual ~MinDistanceConstraint() {} + ~MinDistanceConstraint() override {} /// @return a deep copy of this factor gtsam::NonlinearFactor::shared_ptr clone() const override { diff --git a/tests/simulated2DOriented.h b/tests/simulated2DOriented.h index 27932415b..924a5fe4e 100644 --- a/tests/simulated2DOriented.h +++ b/tests/simulated2DOriented.h @@ -114,7 +114,7 @@ namespace simulated2DOriented { NoiseModelFactor2(model, i1, i2), measured_(measured) { } - virtual ~GenericOdometry() {} + ~GenericOdometry() override {} /// Evaluate error and optionally derivative Vector evaluateError(const VALUE& x1, const VALUE& x2, diff --git a/tests/testExtendedKalmanFilter.cpp b/tests/testExtendedKalmanFilter.cpp index 0ea507a36..f0c1b4b70 100644 --- a/tests/testExtendedKalmanFilter.cpp +++ b/tests/testExtendedKalmanFilter.cpp @@ -120,7 +120,7 @@ public: Q_invsqrt_ = inverse_square_root(Q_); } - virtual ~NonlinearMotionModel() {} + ~NonlinearMotionModel() override {} // Calculate the next state prediction using the nonlinear function f() Point2 f(const Point2& x_t0) const { @@ -255,7 +255,7 @@ public: R_invsqrt_ = inverse_square_root(R_); } - virtual ~NonlinearMeasurementModel() {} + ~NonlinearMeasurementModel() override {} // Calculate the predicted measurement using the nonlinear function h() // Byproduct: updates Jacobian H, and noiseModel (R) diff --git a/timing/timeVirtual2.cpp b/timing/timeVirtual2.cpp index 303468150..8c7c40246 100644 --- a/timing/timeVirtual2.cpp +++ b/timing/timeVirtual2.cpp @@ -34,7 +34,7 @@ struct DtorTestBase { struct DtorTestDerived : public DtorTestBase { DtorTestDerived() { cout << " DtorTestDerived" << endl; } - virtual ~DtorTestDerived() { cout << " ~DtorTestDerived" << endl; } + ~DtorTestDerived() override { cout << " ~DtorTestDerived" << endl; } }; @@ -47,8 +47,8 @@ struct VirtualBase { struct VirtualDerived : public VirtualBase { double data; VirtualDerived() { data = rand(); } - virtual void method() { data = rand(); } - virtual ~VirtualDerived() { } + void method() override { data = rand(); } + ~VirtualDerived() override { } }; struct NonVirtualBase {