Fix override warnings: modernize-use-override

release/4.3a0
Toni 2021-01-28 23:02:13 -05:00
parent c073473f5b
commit 7f80c906c4
109 changed files with 175 additions and 175 deletions

View File

@ -78,7 +78,7 @@ class UnaryFactor: public NoiseModelFactor1<Pose2> {
UnaryFactor(Key j, double x, double y, const SharedNoiseModel& model): UnaryFactor(Key j, double x, double y, const SharedNoiseModel& model):
NoiseModelFactor1<Pose2>(model, j), mx_(x), my_(y) {} NoiseModelFactor1<Pose2>(model, j), mx_(x), my_(y) {}
virtual ~UnaryFactor() {} ~UnaryFactor() override {}
// Using the NoiseModelFactor1 base class there are two functions that must be overridden. // 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 // The first is the 'evaluateError' function. This function implements the desired measurement

View File

@ -74,7 +74,7 @@ public:
} }
/// Destructor /// Destructor
virtual ~GenericValue() { ~GenericValue() override {
} }
/// equals implementing generic Value interface /// equals implementing generic Value interface

View File

@ -72,7 +72,7 @@ protected:
} }
/// Default destructor doesn't have the noexcept /// Default destructor doesn't have the noexcept
virtual ~ThreadsafeException() noexcept { ~ThreadsafeException() noexcept override {
} }
public: public:
@ -114,7 +114,7 @@ class CholeskyFailed : public gtsam::ThreadsafeException<CholeskyFailed>
{ {
public: public:
CholeskyFailed() noexcept {} CholeskyFailed() noexcept {}
virtual ~CholeskyFailed() noexcept {} ~CholeskyFailed() noexcept override {}
}; };
} // namespace gtsam } // namespace gtsam

View File

@ -155,7 +155,7 @@ namespace gtsam {
public: public:
virtual ~Choice() { ~Choice() override {
#ifdef DT_DEBUG_MEMORY #ifdef DT_DEBUG_MEMORY
std::std::cout << Node::nrNodes << " destructing (Choice) " << this->id() << std::std::endl; std::std::cout << Node::nrNodes << " destructing (Choice) " << this->id() << std::std::endl;
#endif #endif

View File

@ -60,7 +60,7 @@ class GTSAM_EXPORT Cal3Bundler : public Cal3 {
double tol = 1e-5) double tol = 1e-5)
: Cal3(f, f, 0, u0, v0), k1_(k1), k2_(k2), tol_(tol) {} : Cal3(f, f, 0, u0, v0), k1_(k1), k2_(k2), tol_(tol) {}
virtual ~Cal3Bundler() {} ~Cal3Bundler() override {}
/// @} /// @}
/// @name Testable /// @name Testable
@ -141,7 +141,7 @@ class GTSAM_EXPORT Cal3Bundler : public Cal3 {
/// @{ /// @{
/// return DOF, dimensionality of tangent space /// 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 /// return DOF, dimensionality of tangent space
inline static size_t Dim() { return dimension; } inline static size_t Dim() { return dimension; }

View File

@ -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) 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) {} : Base(fx, fy, s, u0, v0, k1, k2, p1, p2, tol) {}
virtual ~Cal3DS2() {} ~Cal3DS2() override {}
/// @} /// @}
/// @name Advanced Constructors /// @name Advanced Constructors
@ -80,7 +80,7 @@ class GTSAM_EXPORT Cal3DS2 : public Cal3DS2_Base {
Vector localCoordinates(const Cal3DS2& T2) const; Vector localCoordinates(const Cal3DS2& T2) const;
/// Return dimensions of calibration manifold object /// 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 /// Return dimensions of calibration manifold object
inline static size_t Dim() { return dimension; } inline static size_t Dim() { return dimension; }

View File

@ -62,7 +62,7 @@ class GTSAM_EXPORT Cal3DS2_Base : public Cal3 {
p2_(p2), p2_(p2),
tol_(tol) {} tol_(tol) {}
virtual ~Cal3DS2_Base() {} ~Cal3DS2_Base() override {}
/// @} /// @}
/// @name Advanced Constructors /// @name Advanced Constructors
@ -132,7 +132,7 @@ class GTSAM_EXPORT Cal3DS2_Base : public Cal3 {
Matrix29 D2d_calibration(const Point2& p) const; Matrix29 D2d_calibration(const Point2& p) const;
/// return DOF, dimensionality of tangent space /// 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 /// return DOF, dimensionality of tangent space
inline static size_t Dim() { return dimension; } inline static size_t Dim() { return dimension; }

View File

@ -73,7 +73,7 @@ class GTSAM_EXPORT Cal3Fisheye : public Cal3 {
k4_(k4), k4_(k4),
tol_(tol) {} tol_(tol) {}
virtual ~Cal3Fisheye() {} ~Cal3Fisheye() override {}
/// @} /// @}
/// @name Advanced Constructors /// @name Advanced Constructors
@ -142,7 +142,7 @@ class GTSAM_EXPORT Cal3Fisheye : public Cal3 {
const Cal3Fisheye& cal); const Cal3Fisheye& cal);
/// print with optional string /// 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 /// assert equality up to a tolerance
bool equals(const Cal3Fisheye& K, double tol = 10e-9) const; 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 /// 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 /// Return dimensions of calibration manifold object
inline static size_t Dim() { return dimension; } inline static size_t Dim() { return dimension; }

View File

@ -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) 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) {} : Base(fx, fy, s, u0, v0, k1, k2, p1, p2), xi_(xi) {}
virtual ~Cal3Unified() {} ~Cal3Unified() override {}
/// @} /// @}
/// @name Advanced Constructors /// @name Advanced Constructors
@ -127,7 +127,7 @@ class GTSAM_EXPORT Cal3Unified : public Cal3DS2_Base {
Vector localCoordinates(const Cal3Unified& T2) const; Vector localCoordinates(const Cal3Unified& T2) const;
/// Return dimensions of calibration manifold object /// 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 /// Return dimensions of calibration manifold object
inline static size_t Dim() { return dimension; } inline static size_t Dim() { return dimension; }

View File

@ -157,7 +157,7 @@ public:
/// @name Standard Interface /// @name Standard Interface
/// @{ /// @{
virtual ~PinholeCamera() { ~PinholeCamera() override {
} }
/// return pose /// return pose

View File

@ -352,7 +352,7 @@ public:
/// @name Standard Interface /// @name Standard Interface
/// @{ /// @{
virtual ~PinholePose() { ~PinholePose() override {
} }
/// return shared pointer to calibration /// return shared pointer to calibration

View File

@ -29,7 +29,7 @@ namespace gtsam {
class InconsistentEliminationRequested : public std::exception { class InconsistentEliminationRequested : public std::exception {
public: public:
InconsistentEliminationRequested() noexcept {} InconsistentEliminationRequested() noexcept {}
virtual ~InconsistentEliminationRequested() noexcept {} ~InconsistentEliminationRequested() noexcept override {}
const char* what() const noexcept override { const char* what() const noexcept override {
return return
"An inference algorithm was called with inconsistent arguments. The\n" "An inference algorithm was called with inconsistent arguments. The\n"

View File

@ -183,7 +183,7 @@ namespace gtsam {
: HessianFactor(factors, Scatter(factors)) {} : HessianFactor(factors, Scatter(factors)) {}
/** Destructor */ /** Destructor */
virtual ~HessianFactor() {} ~HessianFactor() override {}
/** Clone this HessianFactor */ /** Clone this HessianFactor */
GaussianFactor::shared_ptr clone() const override { GaussianFactor::shared_ptr clone() const override {

View File

@ -183,7 +183,7 @@ namespace gtsam {
const VariableSlots& p_variableSlots); const VariableSlots& p_variableSlots);
/** Virtual destructor */ /** Virtual destructor */
virtual ~JacobianFactor() {} ~JacobianFactor() override {}
/** Clone this JacobianFactor */ /** Clone this JacobianFactor */
GaussianFactor::shared_ptr clone() const override { GaussianFactor::shared_ptr clone() const override {

View File

@ -129,7 +129,7 @@ class GTSAM_EXPORT Null : public Base {
typedef boost::shared_ptr<Null> shared_ptr; typedef boost::shared_ptr<Null> shared_ptr;
Null(const ReweightScheme reweight = Block) : Base(reweight) {} Null(const ReweightScheme reweight = Block) : Base(reweight) {}
~Null() {} ~Null() override {}
double weight(double /*error*/) const override { return 1.0; } double weight(double /*error*/) const override { return 1.0; }
double loss(double distance) const override { return 0.5 * distance * distance; } double loss(double distance) const override { return 0.5 * distance * distance; }
void print(const std::string &s) const override; void print(const std::string &s) const override;
@ -286,7 +286,7 @@ class GTSAM_EXPORT GemanMcClure : public Base {
typedef boost::shared_ptr<GemanMcClure> shared_ptr; typedef boost::shared_ptr<GemanMcClure> shared_ptr;
GemanMcClure(double c = 1.0, const ReweightScheme reweight = Block); GemanMcClure(double c = 1.0, const ReweightScheme reweight = Block);
~GemanMcClure() {} ~GemanMcClure() override {}
double weight(double distance) const override; double weight(double distance) const override;
double loss(double distance) const override; double loss(double distance) const override;
void print(const std::string &s) const override; void print(const std::string &s) const override;
@ -316,7 +316,7 @@ class GTSAM_EXPORT DCS : public Base {
typedef boost::shared_ptr<DCS> shared_ptr; typedef boost::shared_ptr<DCS> shared_ptr;
DCS(double c = 1.0, const ReweightScheme reweight = Block); DCS(double c = 1.0, const ReweightScheme reweight = Block);
~DCS() {} ~DCS() override {}
double weight(double distance) const override; double weight(double distance) const override;
double loss(double distance) const override; double loss(double distance) const override;
void print(const std::string &s) const override; void print(const std::string &s) const override;

View File

@ -188,7 +188,7 @@ namespace gtsam {
typedef boost::shared_ptr<Gaussian> shared_ptr; typedef boost::shared_ptr<Gaussian> shared_ptr;
virtual ~Gaussian() {} ~Gaussian() override {}
/** /**
* A Gaussian noise model created by specifying a square root information matrix. * A Gaussian noise model created by specifying a square root information matrix.
@ -300,7 +300,7 @@ namespace gtsam {
typedef boost::shared_ptr<Diagonal> shared_ptr; typedef boost::shared_ptr<Diagonal> shared_ptr;
virtual ~Diagonal() {} ~Diagonal() override {}
/** /**
* A diagonal noise model created by specifying a Vector of sigmas, i.e. * A diagonal noise model created by specifying a Vector of sigmas, i.e.
@ -406,7 +406,7 @@ namespace gtsam {
typedef boost::shared_ptr<Constrained> shared_ptr; typedef boost::shared_ptr<Constrained> shared_ptr;
~Constrained() {} ~Constrained() override {}
/// true if a constrained noise mode, saves slow/clumsy dynamic casting /// true if a constrained noise mode, saves slow/clumsy dynamic casting
bool isConstrained() const override { return true; } bool isConstrained() const override { return true; }
@ -536,7 +536,7 @@ namespace gtsam {
public: public:
virtual ~Isotropic() {} ~Isotropic() override {}
typedef boost::shared_ptr<Isotropic> shared_ptr; typedef boost::shared_ptr<Isotropic> shared_ptr;
@ -600,7 +600,7 @@ namespace gtsam {
typedef boost::shared_ptr<Unit> shared_ptr; typedef boost::shared_ptr<Unit> shared_ptr;
~Unit() {} ~Unit() override {}
/** /**
* Create a unit covariance noise model * Create a unit covariance noise model
@ -671,7 +671,7 @@ namespace gtsam {
: Base(noise->dim()), robust_(robust), noise_(noise) {} : Base(noise->dim()), robust_(robust), noise_(noise) {}
/// Destructor /// Destructor
~Robust() {} ~Robust() override {}
void print(const std::string& name) const override; void print(const std::string& name) const override;
bool equals(const Base& expected, double tol=1e-9) const override; bool equals(const Base& expected, double tol=1e-9) const override;

View File

@ -72,7 +72,7 @@ protected:
public: public:
/* Interface to initialize a solver without a problem */ /* Interface to initialize a solver without a problem */
PCGSolver(const PCGSolverParameters &p); PCGSolver(const PCGSolverParameters &p);
virtual ~PCGSolver() { ~PCGSolver() override {
} }
using IterativeSolver::optimize; using IterativeSolver::optimize;

View File

@ -96,7 +96,7 @@ struct GTSAM_EXPORT DummyPreconditionerParameters : public PreconditionerParamet
typedef PreconditionerParameters Base; typedef PreconditionerParameters Base;
typedef boost::shared_ptr<DummyPreconditionerParameters> shared_ptr; typedef boost::shared_ptr<DummyPreconditionerParameters> shared_ptr;
DummyPreconditionerParameters() : Base() {} DummyPreconditionerParameters() : Base() {}
virtual ~DummyPreconditionerParameters() {} ~DummyPreconditionerParameters() override {}
}; };
/*******************************************************************************************/ /*******************************************************************************************/
@ -108,7 +108,7 @@ public:
public: public:
DummyPreconditioner() : Base() {} DummyPreconditioner() : Base() {}
virtual ~DummyPreconditioner() {} ~DummyPreconditioner() override {}
/* Computation Interfaces for raw vector */ /* Computation Interfaces for raw vector */
void solve(const Vector& y, Vector &x) const override { x = y; } void solve(const Vector& y, Vector &x) const override { x = y; }
@ -124,7 +124,7 @@ public:
struct GTSAM_EXPORT BlockJacobiPreconditionerParameters : public PreconditionerParameters { struct GTSAM_EXPORT BlockJacobiPreconditionerParameters : public PreconditionerParameters {
typedef PreconditionerParameters Base; typedef PreconditionerParameters Base;
BlockJacobiPreconditionerParameters() : Base() {} BlockJacobiPreconditionerParameters() : Base() {}
virtual ~BlockJacobiPreconditionerParameters() {} ~BlockJacobiPreconditionerParameters() override {}
}; };
/*******************************************************************************************/ /*******************************************************************************************/
@ -132,7 +132,7 @@ class GTSAM_EXPORT BlockJacobiPreconditioner : public Preconditioner {
public: public:
typedef Preconditioner Base; typedef Preconditioner Base;
BlockJacobiPreconditioner() ; BlockJacobiPreconditioner() ;
virtual ~BlockJacobiPreconditioner() ; ~BlockJacobiPreconditioner() override ;
/* Computation Interfaces for raw vector */ /* Computation Interfaces for raw vector */
void solve(const Vector& y, Vector &x) const override; void solve(const Vector& y, Vector &x) const override;

View File

@ -80,7 +80,7 @@ namespace gtsam {
SubgraphPreconditioner(const sharedFG& Ab2, const sharedBayesNet& Rc1, const sharedValues& xbar, SubgraphPreconditioner(const sharedFG& Ab2, const sharedBayesNet& Rc1, const sharedValues& xbar,
const SubgraphPreconditionerParameters &p = SubgraphPreconditionerParameters()); const SubgraphPreconditionerParameters &p = SubgraphPreconditionerParameters());
virtual ~SubgraphPreconditioner() {} ~SubgraphPreconditioner() override {}
/** print the object */ /** print the object */
void print(const std::string& s = "SubgraphPreconditioner") const; void print(const std::string& s = "SubgraphPreconditioner") const;

View File

@ -111,7 +111,7 @@ class GTSAM_EXPORT SubgraphSolver : public IterativeSolver {
const Parameters &parameters); const Parameters &parameters);
/// Destructor /// Destructor
virtual ~SubgraphSolver() {} ~SubgraphSolver() override {}
/// @} /// @}
/// @name Implement interface /// @name Implement interface

View File

@ -95,7 +95,7 @@ namespace gtsam {
Key j_; Key j_;
public: public:
IndeterminantLinearSystemException(Key j) noexcept : j_(j) {} IndeterminantLinearSystemException(Key j) noexcept : j_(j) {}
virtual ~IndeterminantLinearSystemException() noexcept {} ~IndeterminantLinearSystemException() noexcept override {}
Key nearbyVariable() const { return j_; } Key nearbyVariable() const { return j_; }
const char* what() const noexcept override; const char* what() const noexcept override;
}; };
@ -110,7 +110,7 @@ namespace gtsam {
InvalidNoiseModel(DenseIndex factorDims, DenseIndex noiseModelDims) : InvalidNoiseModel(DenseIndex factorDims, DenseIndex noiseModelDims) :
factorDims(factorDims), noiseModelDims(noiseModelDims) {} factorDims(factorDims), noiseModelDims(noiseModelDims) {}
virtual ~InvalidNoiseModel() noexcept {} ~InvalidNoiseModel() noexcept override {}
const char* what() const noexcept override; const char* what() const noexcept override;
@ -128,7 +128,7 @@ namespace gtsam {
InvalidMatrixBlock(DenseIndex factorRows, DenseIndex blockRows) : InvalidMatrixBlock(DenseIndex factorRows, DenseIndex blockRows) :
factorRows(factorRows), blockRows(blockRows) {} factorRows(factorRows), blockRows(blockRows) {}
virtual ~InvalidMatrixBlock() noexcept {} ~InvalidMatrixBlock() noexcept override {}
const char* what() const noexcept override; const char* what() const noexcept override;

View File

@ -154,7 +154,7 @@ public:
AHRSFactor(Key rot_i, Key rot_j, Key bias, AHRSFactor(Key rot_i, Key rot_j, Key bias,
const PreintegratedAhrsMeasurements& preintegratedMeasurements); const PreintegratedAhrsMeasurements& preintegratedMeasurements);
virtual ~AHRSFactor() { ~AHRSFactor() override {
} }
/// @return a deep copy of this factor /// @return a deep copy of this factor

View File

@ -92,7 +92,7 @@ public:
Rot3AttitudeFactor() { Rot3AttitudeFactor() {
} }
virtual ~Rot3AttitudeFactor() { ~Rot3AttitudeFactor() override {
} }
/** /**
@ -166,7 +166,7 @@ public:
Pose3AttitudeFactor() { Pose3AttitudeFactor() {
} }
virtual ~Pose3AttitudeFactor() { ~Pose3AttitudeFactor() override {
} }
/** /**

View File

@ -173,7 +173,7 @@ public:
} }
/// Virtual destructor /// 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, Key pose_i, Key vel_i, Key pose_j, Key vel_j, Key bias_i, Key bias_j,
const PreintegratedCombinedMeasurements& preintegratedMeasurements); const PreintegratedCombinedMeasurements& preintegratedMeasurements);
virtual ~CombinedImuFactor() {} ~CombinedImuFactor() override {}
/// @return a deep copy of this factor /// @return a deep copy of this factor
gtsam::NonlinearFactor::shared_ptr clone() const override; gtsam::NonlinearFactor::shared_ptr clone() const override;

View File

@ -51,7 +51,7 @@ public:
/** default constructor - only use for serialization */ /** default constructor - only use for serialization */
GPSFactor(): nT_(0, 0, 0) {} GPSFactor(): nT_(0, 0, 0) {}
virtual ~GPSFactor() {} ~GPSFactor() override {}
/** /**
* @brief Constructor from a measurement in a Cartesian frame. * @brief Constructor from a measurement in a Cartesian frame.
@ -129,7 +129,7 @@ public:
/// default constructor - only use for serialization /// default constructor - only use for serialization
GPSFactor2():nT_(0, 0, 0) {} GPSFactor2():nT_(0, 0, 0) {}
virtual ~GPSFactor2() {} ~GPSFactor2() override {}
/// Constructor from a measurement in a Cartesian frame. /// Constructor from a measurement in a Cartesian frame.
GPSFactor2(Key key, const Point3& gpsIn, const SharedNoiseModel& model) : GPSFactor2(Key key, const Point3& gpsIn, const SharedNoiseModel& model) :

View File

@ -107,7 +107,7 @@ public:
} }
/// Virtual destructor /// Virtual destructor
virtual ~PreintegratedImuMeasurements() { ~PreintegratedImuMeasurements() override {
} }
/// print /// print
@ -196,7 +196,7 @@ public:
ImuFactor(Key pose_i, Key vel_i, Key pose_j, Key vel_j, Key bias, ImuFactor(Key pose_i, Key vel_i, Key pose_j, Key vel_j, Key bias,
const PreintegratedImuMeasurements& preintegratedMeasurements); const PreintegratedImuMeasurements& preintegratedMeasurements);
virtual ~ImuFactor() { ~ImuFactor() override {
} }
/// @return a deep copy of this factor /// @return a deep copy of this factor
@ -274,7 +274,7 @@ public:
ImuFactor2(Key state_i, Key state_j, Key bias, ImuFactor2(Key state_i, Key state_j, Key bias,
const PreintegratedImuMeasurements& preintegratedMeasurements); const PreintegratedImuMeasurements& preintegratedMeasurements);
virtual ~ImuFactor2() { ~ImuFactor2() override {
} }
/// @return a deep copy of this factor /// @return a deep copy of this factor

View File

@ -54,7 +54,7 @@ public:
const imuBias::ConstantBias& biasHat = imuBias::ConstantBias()); const imuBias::ConstantBias& biasHat = imuBias::ConstantBias());
/// Virtual destructor /// Virtual destructor
virtual ~TangentPreintegration() { ~TangentPreintegration() override {
} }
/// @} /// @}

View File

@ -43,7 +43,7 @@ public:
DoglegParams() : DoglegParams() :
deltaInitial(1.0), verbosityDL(SILENT) {} deltaInitial(1.0), verbosityDL(SILENT) {}
virtual ~DoglegParams() {} ~DoglegParams() override {}
void print(const std::string& str = "") const override { void print(const std::string& str = "") const override {
NonlinearOptimizerParams::print(str); NonlinearOptimizerParams::print(str);
@ -103,7 +103,7 @@ public:
/// @{ /// @{
/** Virtual destructor */ /** Virtual destructor */
virtual ~DoglegOptimizer() {} ~DoglegOptimizer() override {}
/** /**
* Perform a single iteration, returning GaussianFactorGraph corresponding to * Perform a single iteration, returning GaussianFactorGraph corresponding to
@ -121,7 +121,7 @@ public:
protected: protected:
/** Access the parameters (base class version) */ /** 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 */ /** Internal function for computing a COLAMD ordering if no ordering is specified */
DoglegParams ensureHasOrdering(DoglegParams params, const NonlinearFactorGraph& graph) const; DoglegParams ensureHasOrdering(DoglegParams params, const NonlinearFactorGraph& graph) const;

View File

@ -71,7 +71,7 @@ protected:
} }
/// Destructor /// Destructor
virtual ~ExpressionFactor() {} ~ExpressionFactor() override {}
/** return the measurement */ /** return the measurement */
const T& measured() const { return measured_; } const T& measured() const { return measured_; }
@ -245,7 +245,7 @@ public:
using ArrayNKeys = std::array<Key, NARY_EXPRESSION_SIZE>; using ArrayNKeys = std::array<Key, NARY_EXPRESSION_SIZE>;
/// Destructor /// Destructor
virtual ~ExpressionFactorN() = default; ~ExpressionFactorN() override = default;
// Don't provide backward compatible evaluateVector(), due to its problematic // Don't provide backward compatible evaluateVector(), due to its problematic
// variable length of optional Jacobian arguments. Vector evaluateError(const // variable length of optional Jacobian arguments. Vector evaluateError(const
@ -330,7 +330,7 @@ public:
throw std::runtime_error( throw std::runtime_error(
"ExpressionFactor2::expression not provided: cannot deserialize."); "ExpressionFactor2::expression not provided: cannot deserialize.");
} }
virtual Expression<T> Expression<T>
expression(const typename ExpressionFactorN<T, A1, A2>::ArrayNKeys &keys) expression(const typename ExpressionFactorN<T, A1, A2>::ArrayNKeys &keys)
const override { const override {
return expression(keys[0], keys[1]); return expression(keys[0], keys[1]);

View File

@ -79,7 +79,7 @@ class GTSAM_EXPORT FunctorizedFactor : public NoiseModelFactor1<T> {
const std::function<R(T, boost::optional<Matrix &>)> func) const std::function<R(T, boost::optional<Matrix &>)> func)
: Base(model, key), measured_(z), noiseModel_(model), func_(func) {} : Base(model, key), measured_(z), noiseModel_(model), func_(func) {}
virtual ~FunctorizedFactor() {} ~FunctorizedFactor() override {}
/// @return a deep copy of this factor /// @return a deep copy of this factor
NonlinearFactor::shared_ptr clone() const override { NonlinearFactor::shared_ptr clone() const override {
@ -183,7 +183,7 @@ class GTSAM_EXPORT FunctorizedFactor2 : public NoiseModelFactor2<T1, T2> {
noiseModel_(model), noiseModel_(model),
func_(func) {} func_(func) {}
virtual ~FunctorizedFactor2() {} ~FunctorizedFactor2() override {}
/// @return a deep copy of this factor /// @return a deep copy of this factor
NonlinearFactor::shared_ptr clone() const override { NonlinearFactor::shared_ptr clone() const override {

View File

@ -70,7 +70,7 @@ public:
/// @{ /// @{
/** Virtual destructor */ /** Virtual destructor */
virtual ~GaussNewtonOptimizer() {} ~GaussNewtonOptimizer() override {}
/** /**
* Perform a single iteration, returning GaussianFactorGraph corresponding to * Perform a single iteration, returning GaussianFactorGraph corresponding to

View File

@ -69,7 +69,7 @@ public:
const LevenbergMarquardtParams& params = LevenbergMarquardtParams()); const LevenbergMarquardtParams& params = LevenbergMarquardtParams());
/** Virtual destructor */ /** Virtual destructor */
virtual ~LevenbergMarquardtOptimizer() { ~LevenbergMarquardtOptimizer() override {
} }
/// @} /// @}

View File

@ -122,7 +122,7 @@ public:
return params; return params;
} }
virtual ~LevenbergMarquardtParams() {} ~LevenbergMarquardtParams() override {}
void print(const std::string& str = "") const override; void print(const std::string& str = "") const override;
/// @name Getters/Setters, mainly for wrappers. Use fields above in C++. /// @name Getters/Setters, mainly for wrappers. Use fields above in C++.

View File

@ -67,7 +67,7 @@ public:
const Values& initialValues, const Parameters& params = Parameters()); const Values& initialValues, const Parameters& params = Parameters());
/// Destructor /// Destructor
virtual ~NonlinearConjugateGradientOptimizer() { ~NonlinearConjugateGradientOptimizer() override {
} }
/** /**

View File

@ -77,7 +77,7 @@ public:
NonlinearEquality() { NonlinearEquality() {
} }
virtual ~NonlinearEquality() { ~NonlinearEquality() override {
} }
/// @name Standard Constructors /// @name Standard Constructors
@ -238,7 +238,7 @@ public:
std::abs(mu)), key), value_(value) { std::abs(mu)), key), value_(value) {
} }
virtual ~NonlinearEquality1() { ~NonlinearEquality1() override {
} }
/// @return a deep copy of this factor /// @return a deep copy of this factor
@ -313,7 +313,7 @@ public:
NonlinearEquality2(Key key1, Key key2, double mu = 1000.0) : NonlinearEquality2(Key key1, Key key2, double mu = 1000.0) :
Base(noiseModel::Constrained::All(traits<X>::dimension, std::abs(mu)), key1, key2) { Base(noiseModel::Constrained::All(traits<X>::dimension, std::abs(mu)), key1, key2) {
} }
virtual ~NonlinearEquality2() { ~NonlinearEquality2() override {
} }
/// @return a deep copy of this factor /// @return a deep copy of this factor

View File

@ -169,7 +169,7 @@ public:
NoiseModelFactor() {} NoiseModelFactor() {}
/** Destructor */ /** Destructor */
virtual ~NoiseModelFactor() {} ~NoiseModelFactor() override {}
/** /**
* Constructor * Constructor
@ -293,7 +293,7 @@ public:
/** Default constructor for I/O only */ /** Default constructor for I/O only */
NoiseModelFactor1() {} NoiseModelFactor1() {}
virtual ~NoiseModelFactor1() {} ~NoiseModelFactor1() override {}
inline Key key() const { return keys_[0]; } inline Key key() const { return keys_[0]; }
@ -387,7 +387,7 @@ public:
NoiseModelFactor2(const SharedNoiseModel& noiseModel, Key j1, Key j2) : NoiseModelFactor2(const SharedNoiseModel& noiseModel, Key j1, Key j2) :
Base(noiseModel, cref_list_of<2>(j1)(j2)) {} Base(noiseModel, cref_list_of<2>(j1)(j2)) {}
virtual ~NoiseModelFactor2() {} ~NoiseModelFactor2() override {}
/** methods to retrieve both keys */ /** methods to retrieve both keys */
inline Key key1() const { return keys_[0]; } inline Key key1() const { return keys_[0]; }
@ -464,7 +464,7 @@ public:
NoiseModelFactor3(const SharedNoiseModel& noiseModel, Key j1, Key j2, Key j3) : NoiseModelFactor3(const SharedNoiseModel& noiseModel, Key j1, Key j2, Key j3) :
Base(noiseModel, cref_list_of<3>(j1)(j2)(j3)) {} Base(noiseModel, cref_list_of<3>(j1)(j2)(j3)) {}
virtual ~NoiseModelFactor3() {} ~NoiseModelFactor3() override {}
/** methods to retrieve keys */ /** methods to retrieve keys */
inline Key key1() const { return keys_[0]; } inline Key key1() const { return keys_[0]; }
@ -543,7 +543,7 @@ public:
NoiseModelFactor4(const SharedNoiseModel& noiseModel, Key j1, Key j2, Key j3, Key j4) : NoiseModelFactor4(const SharedNoiseModel& noiseModel, Key j1, Key j2, Key j3, Key j4) :
Base(noiseModel, cref_list_of<4>(j1)(j2)(j3)(j4)) {} Base(noiseModel, cref_list_of<4>(j1)(j2)(j3)(j4)) {}
virtual ~NoiseModelFactor4() {} ~NoiseModelFactor4() override {}
/** methods to retrieve keys */ /** methods to retrieve keys */
inline Key key1() const { return keys_[0]; } 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) : 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)) {} Base(noiseModel, cref_list_of<5>(j1)(j2)(j3)(j4)(j5)) {}
virtual ~NoiseModelFactor5() {} ~NoiseModelFactor5() override {}
/** methods to retrieve keys */ /** methods to retrieve keys */
inline Key key1() const { return keys_[0]; } 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) : 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)) {} Base(noiseModel, cref_list_of<6>(j1)(j2)(j3)(j4)(j5)(j6)) {}
virtual ~NoiseModelFactor6() {} ~NoiseModelFactor6() override {}
/** methods to retrieve keys */ /** methods to retrieve keys */
inline Key key1() const { return keys_[0]; } inline Key key1() const { return keys_[0]; }

View File

@ -52,7 +52,7 @@ namespace gtsam {
/** default constructor - only use for serialization */ /** default constructor - only use for serialization */
PriorFactor() {} PriorFactor() {}
virtual ~PriorFactor() {} ~PriorFactor() override {}
/** Constructor */ /** Constructor */
PriorFactor(Key key, const VALUE& prior, const SharedNoiseModel& model = nullptr) : PriorFactor(Key key, const VALUE& prior, const SharedNoiseModel& model = nullptr) :

View File

@ -442,7 +442,7 @@ namespace gtsam {
ValuesKeyAlreadyExists(Key key) noexcept : ValuesKeyAlreadyExists(Key key) noexcept :
key_(key) {} key_(key) {}
virtual ~ValuesKeyAlreadyExists() noexcept {} ~ValuesKeyAlreadyExists() noexcept override {}
/// The duplicate key that was attempted to be added /// The duplicate key that was attempted to be added
Key key() const noexcept { return key_; } Key key() const noexcept { return key_; }
@ -465,7 +465,7 @@ namespace gtsam {
ValuesKeyDoesNotExist(const char* operation, Key key) noexcept : ValuesKeyDoesNotExist(const char* operation, Key key) noexcept :
operation_(operation), key_(key) {} operation_(operation), key_(key) {}
virtual ~ValuesKeyDoesNotExist() noexcept {} ~ValuesKeyDoesNotExist() noexcept override {}
/// The key that was attempted to be accessed that does not exist /// The key that was attempted to be accessed that does not exist
Key key() const noexcept { return key_; } Key key() const noexcept { return key_; }
@ -490,7 +490,7 @@ namespace gtsam {
const std::type_info& storedTypeId, const std::type_info& requestedTypeId) noexcept : const std::type_info& storedTypeId, const std::type_info& requestedTypeId) noexcept :
key_(key), storedTypeId_(storedTypeId), requestedTypeId_(requestedTypeId) {} key_(key), storedTypeId_(storedTypeId), requestedTypeId_(requestedTypeId) {}
virtual ~ValuesIncorrectType() noexcept {} ~ValuesIncorrectType() noexcept override {}
/// The key that was attempted to be accessed that does not exist /// The key that was attempted to be accessed that does not exist
Key key() const noexcept { return key_; } Key key() const noexcept { return key_; }
@ -511,7 +511,7 @@ namespace gtsam {
public: public:
DynamicValuesMismatched() noexcept {} DynamicValuesMismatched() noexcept {}
virtual ~DynamicValuesMismatched() noexcept {} ~DynamicValuesMismatched() noexcept override {}
const char* what() const noexcept override { const char* what() const noexcept override {
return "The Values 'this' and the argument passed to Values::localCoordinates have mismatched keys and values"; 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) { M1_(M1), N1_(N1), M2_(M2), N2_(N2) {
} }
virtual ~NoMatchFoundForFixed() noexcept { ~NoMatchFoundForFixed() noexcept override {
} }
GTSAM_EXPORT const char* what() const noexcept override; GTSAM_EXPORT const char* what() const noexcept override;

View File

@ -100,7 +100,7 @@ namespace gtsam {
/// @{ /// @{
/// Destructor /// Destructor
virtual ~WhiteNoiseFactor() { ~WhiteNoiseFactor() override {
} }
/// @} /// @}

View File

@ -131,7 +131,7 @@ class ConstantExpression: public ExpressionNode<T> {
public: public:
/// Destructor /// Destructor
virtual ~ConstantExpression() { ~ConstantExpression() override {
} }
/// Print /// Print
@ -172,7 +172,7 @@ class LeafExpression: public ExpressionNode<T> {
public: public:
/// Destructor /// Destructor
virtual ~LeafExpression() { ~LeafExpression() override {
} }
/// Print /// Print
@ -244,7 +244,7 @@ class UnaryExpression: public ExpressionNode<T> {
public: public:
/// Destructor /// Destructor
virtual ~UnaryExpression() { ~UnaryExpression() override {
} }
/// Print /// Print
@ -353,7 +353,7 @@ class BinaryExpression: public ExpressionNode<T> {
public: public:
/// Destructor /// Destructor
virtual ~BinaryExpression() { ~BinaryExpression() override {
} }
/// Print /// Print
@ -460,7 +460,7 @@ class TernaryExpression: public ExpressionNode<T> {
public: public:
/// Destructor /// Destructor
virtual ~TernaryExpression() { ~TernaryExpression() override {
} }
/// Print /// Print
@ -571,7 +571,7 @@ class ScalarMultiplyNode : public ExpressionNode<T> {
} }
/// Destructor /// Destructor
virtual ~ScalarMultiplyNode() {} ~ScalarMultiplyNode() override {}
/// Print /// Print
void print(const std::string& indent = "") const override { void print(const std::string& indent = "") const override {
@ -659,7 +659,7 @@ class BinarySumNode : public ExpressionNode<T> {
} }
/// Destructor /// Destructor
virtual ~BinarySumNode() {} ~BinarySumNode() override {}
/// Print /// Print
void print(const std::string& indent = "") const override { void print(const std::string& indent = "") const override {

View File

@ -77,7 +77,7 @@ template<> struct traits<CallConfig> : public Testable<CallConfig> {};
struct Record: public internal::CallRecordImplementor<Record, Cols> { struct Record: public internal::CallRecordImplementor<Record, Cols> {
Record() : cc(0, 0) {} Record() : cc(0, 0) {}
virtual ~Record() { ~Record() override {
} }
void print(const std::string& indent) const { void print(const std::string& indent) const {
} }

View File

@ -59,7 +59,7 @@ class BearingRangeFactor
this->initialize(expression({{key1, key2}})); this->initialize(expression({{key1, key2}}));
} }
virtual ~BearingRangeFactor() {} ~BearingRangeFactor() override {}
/// @return a deep copy of this factor /// @return a deep copy of this factor
gtsam::NonlinearFactor::shared_ptr clone() const override { gtsam::NonlinearFactor::shared_ptr clone() const override {

View File

@ -118,7 +118,7 @@ class RangeFactorWithTransform : public ExpressionFactorN<T, A1, A2> {
this->initialize(expression({key1, key2})); this->initialize(expression({key1, key2}));
} }
virtual ~RangeFactorWithTransform() {} ~RangeFactorWithTransform() override {}
/// @return a deep copy of this factor /// @return a deep copy of this factor
gtsam::NonlinearFactor::shared_ptr clone() const override { gtsam::NonlinearFactor::shared_ptr clone() const override {

View File

@ -90,7 +90,7 @@ public:
} }
/// Destructor /// Destructor
virtual ~ShonanGaugeFactor() {} ~ShonanGaugeFactor() override {}
/// Calculate the error of the factor: always zero /// Calculate the error of the factor: always zero
double error(const Values &c) const override { return 0; } double error(const Values &c) const override { return 0; }

View File

@ -49,7 +49,7 @@ namespace gtsam {
/** constructor - Creates the equivalent AntiFactor from an existing factor */ /** constructor - Creates the equivalent AntiFactor from an existing factor */
AntiFactor(NonlinearFactor::shared_ptr factor) : Base(factor->keys()), factor_(factor) {} AntiFactor(NonlinearFactor::shared_ptr factor) : Base(factor->keys()), factor_(factor) {}
virtual ~AntiFactor() {} ~AntiFactor() override {}
/// @return a deep copy of this factor /// @return a deep copy of this factor
gtsam::NonlinearFactor::shared_ptr clone() const override { gtsam::NonlinearFactor::shared_ptr clone() const override {

View File

@ -68,7 +68,7 @@ namespace gtsam {
Base(model, key1, key2), measured_(measured) { Base(model, key1, key2), measured_(measured) {
} }
virtual ~BetweenFactor() {} ~BetweenFactor() override {}
/// @return a deep copy of this factor /// @return a deep copy of this factor
gtsam::NonlinearFactor::shared_ptr clone() const override { gtsam::NonlinearFactor::shared_ptr clone() const override {

View File

@ -44,7 +44,7 @@ struct BoundingConstraint1: public NoiseModelFactor1<VALUE> {
threshold_(threshold), isGreaterThan_(isGreaterThan) { threshold_(threshold), isGreaterThan_(isGreaterThan) {
} }
virtual ~BoundingConstraint1() {} ~BoundingConstraint1() override {}
inline double threshold() const { return threshold_; } inline double threshold() const { return threshold_; }
inline bool isGreaterThan() const { return isGreaterThan_; } inline bool isGreaterThan() const { return isGreaterThan_; }
@ -112,7 +112,7 @@ struct BoundingConstraint2: public NoiseModelFactor2<VALUE1, VALUE2> {
: Base(noiseModel::Constrained::All(1, mu), key1, key2), : Base(noiseModel::Constrained::All(1, mu), key1, key2),
threshold_(threshold), isGreaterThan_(isGreaterThan) {} threshold_(threshold), isGreaterThan_(isGreaterThan) {}
virtual ~BoundingConstraint2() {} ~BoundingConstraint2() override {}
inline double threshold() const { return threshold_; } inline double threshold() const { return threshold_; }
inline bool isGreaterThan() const { return isGreaterThan_; } inline bool isGreaterThan() const { return isGreaterThan_; }

View File

@ -57,7 +57,7 @@ public:
Base(model, key1, key2), measuredE_(measuredE) { Base(model, key1, key2), measuredE_(measuredE) {
} }
virtual ~EssentialMatrixConstraint() { ~EssentialMatrixConstraint() override {
} }
/// @return a deep copy of this factor /// @return a deep copy of this factor

View File

@ -96,7 +96,7 @@ public:
///< constructor that takes doubles x,y to make a Point2 ///< constructor that takes doubles x,y to make a Point2
GeneralSFMFactor(double x, double y) : measured_(x, y) {} GeneralSFMFactor(double x, double y) : measured_(x, y) {}
virtual ~GeneralSFMFactor() {} ///< destructor ~GeneralSFMFactor() override {} ///< destructor
/// @return a deep copy of this factor /// @return a deep copy of this factor
gtsam::NonlinearFactor::shared_ptr clone() const override { gtsam::NonlinearFactor::shared_ptr clone() const override {
@ -230,7 +230,7 @@ public:
Base(model, poseKey, landmarkKey, calibKey), measured_(measured) {} Base(model, poseKey, landmarkKey, calibKey), measured_(measured) {}
GeneralSFMFactor2():measured_(0.0,0.0) {} ///< default constructor GeneralSFMFactor2():measured_(0.0,0.0) {} ///< default constructor
virtual ~GeneralSFMFactor2() {} ///< destructor ~GeneralSFMFactor2() override {} ///< destructor
/// @return a deep copy of this factor /// @return a deep copy of this factor
gtsam::NonlinearFactor::shared_ptr clone() const override { gtsam::NonlinearFactor::shared_ptr clone() const override {

View File

@ -63,7 +63,7 @@ public:
boost::optional<double> beta = boost::none); boost::optional<double> beta = boost::none);
/// Destructor /// Destructor
virtual ~KarcherMeanFactor() {} ~KarcherMeanFactor() override {}
/// Calculate the error of the factor: always zero /// Calculate the error of the factor: always zero
double error(const Values &c) const override { return 0; } double error(const Values &c) const override { return 0; }

View File

@ -30,7 +30,7 @@ public:
/// Constructor /// Constructor
OrientedPlane3Factor() { OrientedPlane3Factor() {
} }
virtual ~OrientedPlane3Factor() {} ~OrientedPlane3Factor() override {}
/// Constructor with measured plane coefficients (a,b,c,d), noise model, pose symbol /// Constructor with measured plane coefficients (a,b,c,d), noise model, pose symbol
OrientedPlane3Factor(const Vector&z, const SharedGaussian& noiseModel, OrientedPlane3Factor(const Vector&z, const SharedGaussian& noiseModel,

View File

@ -47,7 +47,7 @@ public:
PoseRotationPrior(Key key, const POSE& pose_z, const SharedNoiseModel& model) PoseRotationPrior(Key key, const POSE& pose_z, const SharedNoiseModel& model)
: Base(model, key), measured_(pose_z.rotation()) {} : Base(model, key), measured_(pose_z.rotation()) {}
virtual ~PoseRotationPrior() {} ~PoseRotationPrior() override {}
/// @return a deep copy of this factor /// @return a deep copy of this factor
gtsam::NonlinearFactor::shared_ptr clone() const override { gtsam::NonlinearFactor::shared_ptr clone() const override {

View File

@ -49,7 +49,7 @@ public:
: Base(model, key), measured_(pose_z.translation()) { : Base(model, key), measured_(pose_z.translation()) {
} }
virtual ~PoseTranslationPrior() {} ~PoseTranslationPrior() override {}
const Translation& measured() const { return measured_; } const Translation& measured() const { return measured_; }

View File

@ -97,7 +97,7 @@ namespace gtsam {
throwCheirality_(throwCheirality), verboseCheirality_(verboseCheirality) {} throwCheirality_(throwCheirality), verboseCheirality_(verboseCheirality) {}
/** Virtual destructor */ /** Virtual destructor */
virtual ~GenericProjectionFactor() {} ~GenericProjectionFactor() override {}
/// @return a deep copy of this factor /// @return a deep copy of this factor
gtsam::NonlinearFactor::shared_ptr clone() const override { gtsam::NonlinearFactor::shared_ptr clone() const override {

View File

@ -87,7 +87,7 @@ public:
: Base(noiseModel::Isotropic::Sigma(traits<POINT>::dimension, sigma), : Base(noiseModel::Isotropic::Sigma(traits<POINT>::dimension, sigma),
globalKey, transKey, localKey) {} globalKey, transKey, localKey) {}
virtual ~ReferenceFrameFactor(){} ~ReferenceFrameFactor() override{}
NonlinearFactor::shared_ptr clone() const override { NonlinearFactor::shared_ptr clone() const override {
return boost::static_pointer_cast<NonlinearFactor>( return boost::static_pointer_cast<NonlinearFactor>(

View File

@ -59,7 +59,7 @@ public:
} }
/// Destructor /// Destructor
virtual ~RegularImplicitSchurFactor() { ~RegularImplicitSchurFactor() override {
} }
std::vector<MatrixZD, Eigen::aligned_allocator<MatrixZD> >& FBlocks() const { std::vector<MatrixZD, Eigen::aligned_allocator<MatrixZD> >& FBlocks() const {

View File

@ -112,7 +112,7 @@ protected:
} }
/// Virtual destructor, subclasses from NonlinearFactor /// Virtual destructor, subclasses from NonlinearFactor
virtual ~SmartFactorBase() { ~SmartFactorBase() override {
} }
/** /**

View File

@ -90,7 +90,7 @@ public:
result_(TriangulationResult::Degenerate()) {} result_(TriangulationResult::Degenerate()) {}
/** Virtual destructor */ /** Virtual destructor */
virtual ~SmartProjectionFactor() { ~SmartProjectionFactor() override {
} }
/** /**

View File

@ -94,7 +94,7 @@ public:
} }
/** Virtual destructor */ /** Virtual destructor */
virtual ~SmartProjectionPoseFactor() { ~SmartProjectionPoseFactor() override {
} }
/** /**

View File

@ -88,7 +88,7 @@ public:
throwCheirality_(throwCheirality), verboseCheirality_(verboseCheirality) {} throwCheirality_(throwCheirality), verboseCheirality_(verboseCheirality) {}
/** Virtual destructor */ /** Virtual destructor */
virtual ~GenericStereoFactor() {} ~GenericStereoFactor() override {}
/// @return a deep copy of this factor /// @return a deep copy of this factor
gtsam::NonlinearFactor::shared_ptr clone() const override { gtsam::NonlinearFactor::shared_ptr clone() const override {

View File

@ -86,7 +86,7 @@ public:
} }
/** Virtual destructor */ /** Virtual destructor */
virtual ~TriangulationFactor() { ~TriangulationFactor() override {
} }
/// @return a deep copy of this factor /// @return a deep copy of this factor

View File

@ -95,7 +95,7 @@ namespace gtsam {
return FromIteratorsShared(keys.begin(), keys.end(), nrFrontals); return FromIteratorsShared(keys.begin(), keys.end(), nrFrontals);
} }
virtual ~SymbolicConditional() {} ~SymbolicConditional() override {}
/// Copy this object as its actual derived type. /// Copy this object as its actual derived type.
SymbolicFactor::shared_ptr clone() const { return boost::make_shared<This>(*this); } SymbolicFactor::shared_ptr clone() const { return boost::make_shared<This>(*this); }

View File

@ -67,7 +67,7 @@ namespace gtsam {
Constraint(); Constraint();
/// Virtual destructor /// Virtual destructor
virtual ~Constraint() {} ~Constraint() override {}
/// @} /// @}
/// @name Standard Interface /// @name Standard Interface

View File

@ -48,7 +48,7 @@ public:
assert(model->dim() == 9); assert(model->dim() == 9);
} }
virtual ~FullIMUFactor() {} ~FullIMUFactor() override {}
/// @return a deep copy of this factor /// @return a deep copy of this factor
gtsam::NonlinearFactor::shared_ptr clone() const override { gtsam::NonlinearFactor::shared_ptr clone() const override {

View File

@ -41,7 +41,7 @@ public:
double dt, const Key& key1, const Key& key2, const SharedNoiseModel& model) 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) {} : 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 /// @return a deep copy of this factor
gtsam::NonlinearFactor::shared_ptr clone() const override { gtsam::NonlinearFactor::shared_ptr clone() const override {

View File

@ -33,7 +33,7 @@ public:
Base(noiseModel::Constrained::All(6, std::abs(mu)), gKey1, gKey, Base(noiseModel::Constrained::All(6, std::abs(mu)), gKey1, gKey,
xiKey), h_(h) { xiKey), h_(h) {
} }
virtual ~Reconstruction() {} ~Reconstruction() override {}
/// @return a deep copy of this factor /// @return a deep copy of this factor
gtsam::NonlinearFactor::shared_ptr clone() const override { gtsam::NonlinearFactor::shared_ptr clone() const override {
@ -95,7 +95,7 @@ public:
Base(noiseModel::Constrained::All(6, std::abs(mu)), xiKey1, xiKey_1, gKey), Base(noiseModel::Constrained::All(6, std::abs(mu)), xiKey1, xiKey_1, gKey),
h_(h), Inertia_(Inertia), Fu_(Fu), m_(m) { h_(h), Inertia_(Inertia), Fu_(Fu), m_(m) {
} }
virtual ~DiscreteEulerPoincareHelicopter() {} ~DiscreteEulerPoincareHelicopter() override {}
/// @return a deep copy of this factor /// @return a deep copy of this factor
gtsam::NonlinearFactor::shared_ptr clone() const override { gtsam::NonlinearFactor::shared_ptr clone() const override {

View File

@ -70,7 +70,7 @@ public:
VelocityConstraint(Key key1, Key key2, double dt, const gtsam::SharedNoiseModel& model) VelocityConstraint(Key key1, Key key2, double dt, const gtsam::SharedNoiseModel& model)
: Base(model, key1, key2), dt_(dt), integration_mode_(dynamics::TRAPEZOIDAL) {} : Base(model, key1, key2), dt_(dt), integration_mode_(dynamics::TRAPEZOIDAL) {}
virtual ~VelocityConstraint() {} ~VelocityConstraint() override {}
/// @return a deep copy of this factor /// @return a deep copy of this factor
gtsam::NonlinearFactor::shared_ptr clone() const override { gtsam::NonlinearFactor::shared_ptr clone() const override {

View File

@ -28,7 +28,7 @@ public:
///TODO: comment ///TODO: comment
VelocityConstraint3(Key key1, Key key2, Key velKey, double dt, double mu = 1000.0) 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) {} : Base(noiseModel::Constrained::All(1, std::abs(mu)), key1, key2, velKey), dt_(dt) {}
virtual ~VelocityConstraint3() {} ~VelocityConstraint3() override {}
/// @return a deep copy of this factor /// @return a deep copy of this factor
gtsam::NonlinearFactor::shared_ptr clone() const override { gtsam::NonlinearFactor::shared_ptr clone() const override {

View File

@ -29,7 +29,7 @@ public:
InfeasibleInitialValues() { InfeasibleInitialValues() {
} }
virtual ~InfeasibleInitialValues() noexcept { ~InfeasibleInitialValues() noexcept override {
} }
const char *what() const noexcept override { const char *what() const noexcept override {

View File

@ -25,7 +25,7 @@ class InfeasibleOrUnboundedProblem: public ThreadsafeException<
public: public:
InfeasibleOrUnboundedProblem() { InfeasibleOrUnboundedProblem() {
} }
virtual ~InfeasibleOrUnboundedProblem() noexcept { ~InfeasibleOrUnboundedProblem() noexcept override {
} }
const char* what() const noexcept override { const char* what() const noexcept override {

View File

@ -84,7 +84,7 @@ public:
} }
/** Virtual destructor */ /** Virtual destructor */
virtual ~LinearCost() { ~LinearCost() override {
} }
/** equals */ /** equals */

View File

@ -85,7 +85,7 @@ public:
} }
/** Virtual destructor */ /** Virtual destructor */
virtual ~LinearEquality() { ~LinearEquality() override {
} }
/** equals */ /** equals */

View File

@ -96,7 +96,7 @@ public:
} }
/** Virtual destructor */ /** Virtual destructor */
virtual ~LinearInequality() { ~LinearInequality() override {
} }
/** equals */ /** equals */

View File

@ -25,7 +25,7 @@ public:
QPSParserException() { QPSParserException() {
} }
virtual ~QPSParserException() noexcept { ~QPSParserException() noexcept override {
} }
const char *what() const noexcept override { const char *what() const noexcept override {

View File

@ -38,7 +38,7 @@ public:
FixedLagSmoother(smootherLag), parameters_(parameters), enforceConsistency_(enforceConsistency) { }; FixedLagSmoother(smootherLag), parameters_(parameters), enforceConsistency_(enforceConsistency) { };
/** destructor */ /** destructor */
virtual ~BatchFixedLagSmoother() { }; ~BatchFixedLagSmoother() override { };
/** Print the factor for debugging and testing (implementing Testable) */ /** Print the factor for debugging and testing (implementing Testable) */
void print(const std::string& s = "BatchFixedLagSmoother:\n", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override; void print(const std::string& s = "BatchFixedLagSmoother:\n", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override;

View File

@ -64,7 +64,7 @@ public:
ConcurrentBatchFilter(const LevenbergMarquardtParams& parameters = LevenbergMarquardtParams()) : parameters_(parameters) {}; ConcurrentBatchFilter(const LevenbergMarquardtParams& parameters = LevenbergMarquardtParams()) : parameters_(parameters) {};
/** Default destructor */ /** Default destructor */
virtual ~ConcurrentBatchFilter() {}; ~ConcurrentBatchFilter() override {};
/** Implement a GTSAM standard 'print' function */ /** Implement a GTSAM standard 'print' function */
void print(const std::string& s = "Concurrent Batch Filter:\n", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override; 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. * Perform any required operations before the synchronization process starts.
* Called by 'synchronize' * Called by 'synchronize'
*/ */
virtual void presync() override; void presync() override;
/** /**
* Populate the provided containers with factors that constitute the filter branch summarization * 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. * Perform any required operations after the synchronization process finishes.
* Called by 'synchronize' * Called by 'synchronize'
*/ */
virtual void postsync() override; void postsync() override;
protected: protected:

View File

@ -57,7 +57,7 @@ public:
ConcurrentBatchSmoother(const LevenbergMarquardtParams& parameters = LevenbergMarquardtParams()) : parameters_(parameters) {}; ConcurrentBatchSmoother(const LevenbergMarquardtParams& parameters = LevenbergMarquardtParams()) : parameters_(parameters) {};
/** Default destructor */ /** Default destructor */
virtual ~ConcurrentBatchSmoother() {}; ~ConcurrentBatchSmoother() override {};
/** Implement a GTSAM standard 'print' function */ /** Implement a GTSAM standard 'print' function */
void print(const std::string& s = "Concurrent Batch Smoother:\n", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override; 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. * Perform any required operations before the synchronization process starts.
* Called by 'synchronize' * Called by 'synchronize'
*/ */
virtual void presync() override; void presync() override;
/** /**
* Populate the provided containers with factors that constitute the smoother branch summarization * 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. * Perform any required operations after the synchronization process finishes.
* Called by 'synchronize' * Called by 'synchronize'
*/ */
virtual void postsync() override; void postsync() override;
protected: protected:

View File

@ -64,7 +64,7 @@ public:
ConcurrentIncrementalFilter(const ISAM2Params& parameters = ISAM2Params()) : isam2_(parameters) {}; ConcurrentIncrementalFilter(const ISAM2Params& parameters = ISAM2Params()) : isam2_(parameters) {};
/** Default destructor */ /** Default destructor */
virtual ~ConcurrentIncrementalFilter() {}; ~ConcurrentIncrementalFilter() override {};
/** Implement a GTSAM standard 'print' function */ /** Implement a GTSAM standard 'print' function */
void print(const std::string& s = "Concurrent Incremental Filter:\n", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override; void print(const std::string& s = "Concurrent Incremental Filter:\n", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override;

View File

@ -54,7 +54,7 @@ public:
ConcurrentIncrementalSmoother(const ISAM2Params& parameters = ISAM2Params()) : isam2_(parameters) {}; ConcurrentIncrementalSmoother(const ISAM2Params& parameters = ISAM2Params()) : isam2_(parameters) {};
/** Default destructor */ /** Default destructor */
virtual ~ConcurrentIncrementalSmoother() {}; ~ConcurrentIncrementalSmoother() override {};
/** Implement a GTSAM standard 'print' function */ /** Implement a GTSAM standard 'print' function */
void print(const std::string& s = "Concurrent Incremental Smoother:\n", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override; void print(const std::string& s = "Concurrent Incremental Smoother:\n", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override;

View File

@ -44,15 +44,15 @@ public:
} }
/** destructor */ /** destructor */
virtual ~IncrementalFixedLagSmoother() { ~IncrementalFixedLagSmoother() override {
} }
/** Print the factor for debugging and testing (implementing Testable) */ /** 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; const KeyFormatter& keyFormatter = DefaultKeyFormatter) const override;
/** Check if two IncrementalFixedLagSmoother Objects are equal */ /** 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. * Add new factors, updating the solution and re-linearizing as needed.

View File

@ -53,7 +53,7 @@ public:
*/ */
LinearizedGaussianFactor(const GaussianFactor::shared_ptr& gaussian, const Values& lin_points); LinearizedGaussianFactor(const GaussianFactor::shared_ptr& gaussian, const Values& lin_points);
virtual ~LinearizedGaussianFactor() {}; ~LinearizedGaussianFactor() override {};
// access functions // access functions
const Values& linearizationPoint() const { return lin_points_; } const Values& linearizationPoint() const { return lin_points_; }
@ -109,7 +109,7 @@ public:
*/ */
LinearizedJacobianFactor(const JacobianFactor::shared_ptr& jacobian, const Values& lin_points); LinearizedJacobianFactor(const JacobianFactor::shared_ptr& jacobian, const Values& lin_points);
virtual ~LinearizedJacobianFactor() {} ~LinearizedJacobianFactor() override {}
/// @return a deep copy of this factor /// @return a deep copy of this factor
gtsam::NonlinearFactor::shared_ptr clone() const override { gtsam::NonlinearFactor::shared_ptr clone() const override {
@ -199,7 +199,7 @@ public:
*/ */
LinearizedHessianFactor(const HessianFactor::shared_ptr& hessian, const Values& lin_points); LinearizedHessianFactor(const HessianFactor::shared_ptr& hessian, const Values& lin_points);
virtual ~LinearizedHessianFactor() {} ~LinearizedHessianFactor() override {}
/// @return a deep copy of this factor /// @return a deep copy of this factor
gtsam::NonlinearFactor::shared_ptr clone() const override { gtsam::NonlinearFactor::shared_ptr clone() const override {

View File

@ -78,7 +78,7 @@ public:
flag_bump_up_near_zero_probs) { flag_bump_up_near_zero_probs) {
} }
virtual ~BetweenFactorEM() { ~BetweenFactorEM() override {
} }
/** implement functions needed for Testable */ /** implement functions needed for Testable */

View File

@ -50,7 +50,7 @@ namespace gtsam {
Base(model, posekey, biaskey), measured_(measured) { Base(model, posekey, biaskey), measured_(measured) {
} }
virtual ~BiasedGPSFactor() {} ~BiasedGPSFactor() override {}
/** implement functions needed for Testable */ /** implement functions needed for Testable */

View File

@ -29,7 +29,7 @@ public:
/** standard binary constructor */ /** standard binary constructor */
DummyFactor(const Key& key1, size_t dim1, const Key& key2, size_t dim2); DummyFactor(const Key& key1, size_t dim1, const Key& key2, size_t dim2);
virtual ~DummyFactor() {} ~DummyFactor() override {}
// testable // testable

View File

@ -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), 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) { } Bias_initial_(Bias_initial), body_P_sensor_(body_P_sensor) { }
virtual ~EquivInertialNavFactor_GlobalVel() {} ~EquivInertialNavFactor_GlobalVel() override {}
/** implement functions needed for Testable */ /** implement functions needed for Testable */

View File

@ -66,7 +66,7 @@ public:
Base(calcDiscreteNoiseModel(model, delta_t), key1, key2), dt_(delta_t), tau_(tau) { Base(calcDiscreteNoiseModel(model, delta_t), key1, key2), dt_(delta_t), tau_(tau) {
} }
virtual ~GaussMarkov1stOrderFactor() {} ~GaussMarkov1stOrderFactor() override {}
/** implement functions needed for Testable */ /** implement functions needed for Testable */

View File

@ -109,7 +109,7 @@ public:
Pose1, Vel1, IMUBias1, Pose2, Vel2), measurement_acc_(measurement_acc), measurement_gyro_(measurement_gyro), 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) { } 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 */ /** implement functions needed for Testable */

View File

@ -62,7 +62,7 @@ public:
Base(model, poseKey, pointKey, invDepthKey), measured_(measured), K_(K) {} Base(model, poseKey, pointKey, invDepthKey), measured_(measured), K_(K) {}
/** Virtual destructor */ /** Virtual destructor */
virtual ~InvDepthFactor3() {} ~InvDepthFactor3() override {}
/** /**
* print * print

View File

@ -58,7 +58,7 @@ public:
Base(model, poseKey, landmarkKey), measured_(measured), K_(K) {} Base(model, poseKey, landmarkKey), measured_(measured), K_(K) {}
/** Virtual destructor */ /** Virtual destructor */
virtual ~InvDepthFactorVariant1() {} ~InvDepthFactorVariant1() override {}
/** /**
* print * print

View File

@ -61,7 +61,7 @@ public:
Base(model, poseKey, landmarkKey), measured_(measured), K_(K), referencePoint_(referencePoint) {} Base(model, poseKey, landmarkKey), measured_(measured), K_(K), referencePoint_(referencePoint) {}
/** Virtual destructor */ /** Virtual destructor */
virtual ~InvDepthFactorVariant2() {} ~InvDepthFactorVariant2() override {}
/** /**
* print * print

View File

@ -60,7 +60,7 @@ public:
Base(model, poseKey, landmarkKey), measured_(measured), K_(K) {} Base(model, poseKey, landmarkKey), measured_(measured), K_(K) {}
/** Virtual destructor */ /** Virtual destructor */
virtual ~InvDepthFactorVariant3a() {} ~InvDepthFactorVariant3a() override {}
/** /**
* print * print
@ -180,7 +180,7 @@ public:
Base(model, poseKey1, poseKey2, landmarkKey), measured_(measured), K_(K) {} Base(model, poseKey1, poseKey2, landmarkKey), measured_(measured), K_(K) {}
/** Virtual destructor */ /** Virtual destructor */
virtual ~InvDepthFactorVariant3b() {} ~InvDepthFactorVariant3b() override {}
/** /**
* print * print

View File

@ -98,7 +98,7 @@ namespace gtsam {
throwCheirality_(throwCheirality), verboseCheirality_(verboseCheirality) {} throwCheirality_(throwCheirality), verboseCheirality_(verboseCheirality) {}
/** Virtual destructor */ /** Virtual destructor */
virtual ~MultiProjectionFactor() {} ~MultiProjectionFactor() override {}
/// @return a deep copy of this factor /// @return a deep copy of this factor
NonlinearFactor::shared_ptr clone() const override { NonlinearFactor::shared_ptr clone() const override {

View File

@ -66,7 +66,7 @@ namespace gtsam {
public: public:
virtual ~PartialPriorFactor() {} ~PartialPriorFactor() override {}
/** Single Element Constructor: acts on a single parameter specified by idx */ /** Single Element Constructor: acts on a single parameter specified by idx */
PartialPriorFactor(Key key, size_t idx, double prior, const SharedNoiseModel& model) : PartialPriorFactor(Key key, size_t idx, double prior, const SharedNoiseModel& model) :

View File

@ -56,7 +56,7 @@ namespace gtsam {
Base(model, key1, key2), measured_(measured), body_P_sensor_(body_P_sensor) { Base(model, key1, key2), measured_(measured), body_P_sensor_(body_P_sensor) {
} }
virtual ~PoseBetweenFactor() {} ~PoseBetweenFactor() override {}
/// @return a deep copy of this factor /// @return a deep copy of this factor
gtsam::NonlinearFactor::shared_ptr clone() const override { gtsam::NonlinearFactor::shared_ptr clone() const override {

View File

@ -47,7 +47,7 @@ namespace gtsam {
/** default constructor - only use for serialization */ /** default constructor - only use for serialization */
PosePriorFactor() {} PosePriorFactor() {}
virtual ~PosePriorFactor() {} ~PosePriorFactor() override {}
/** Constructor */ /** Constructor */
PosePriorFactor(Key key, const POSE& prior, const SharedNoiseModel& model, PosePriorFactor(Key key, const POSE& prior, const SharedNoiseModel& model,

View File

@ -93,7 +93,7 @@ namespace gtsam {
throwCheirality_(throwCheirality), verboseCheirality_(verboseCheirality) {} throwCheirality_(throwCheirality), verboseCheirality_(verboseCheirality) {}
/** Virtual destructor */ /** Virtual destructor */
virtual ~ProjectionFactorPPP() {} ~ProjectionFactorPPP() override {}
/// @return a deep copy of this factor /// @return a deep copy of this factor
NonlinearFactor::shared_ptr clone() const override { NonlinearFactor::shared_ptr clone() const override {

View File

@ -88,7 +88,7 @@ namespace gtsam {
throwCheirality_(throwCheirality), verboseCheirality_(verboseCheirality) {} throwCheirality_(throwCheirality), verboseCheirality_(verboseCheirality) {}
/** Virtual destructor */ /** Virtual destructor */
virtual ~ProjectionFactorPPPC() {} ~ProjectionFactorPPPC() override {}
/// @return a deep copy of this factor /// @return a deep copy of this factor
NonlinearFactor::shared_ptr clone() const override { NonlinearFactor::shared_ptr clone() const override {

View File

@ -40,7 +40,7 @@ public:
RelativeElevationFactor(Key poseKey, Key pointKey, double measured, RelativeElevationFactor(Key poseKey, Key pointKey, double measured,
const SharedNoiseModel& model); const SharedNoiseModel& model);
virtual ~RelativeElevationFactor() {} ~RelativeElevationFactor() override {}
/// @return a deep copy of this factor /// @return a deep copy of this factor
gtsam::NonlinearFactor::shared_ptr clone() const override { gtsam::NonlinearFactor::shared_ptr clone() const override {

View File

@ -54,7 +54,7 @@ class SmartRangeFactor: public NoiseModelFactor {
NoiseModelFactor(noiseModel::Isotropic::Sigma(1, s)), variance_(s * s) { NoiseModelFactor(noiseModel::Isotropic::Sigma(1, s)), variance_(s * s) {
} }
virtual ~SmartRangeFactor() { ~SmartRangeFactor() override {
} }
/// Add a range measurement to a pose with given key. /// Add a range measurement to a pose with given key.

View File

@ -93,7 +93,7 @@ public:
} }
/** Virtual destructor */ /** Virtual destructor */
virtual ~SmartStereoProjectionFactor() { ~SmartStereoProjectionFactor() override {
} }
/** /**

Some files were not shown because too many files have changed in this diff Show More