From a8eb98aceac9c8e557468f2dff490e993060447c Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sat, 11 Feb 2023 12:32:50 -0800 Subject: [PATCH] Fixed warnings that arise from stricter compiler flags --- CppUnitLite/Test.h | 3 +- CppUnitLite/TestResult.h | 2 +- cmake/GtsamBuildTypes.cmake | 2 + gtsam/base/DSFMap.h | 4 +- gtsam/base/concepts.h | 10 ++-- gtsam/base/types.cpp | 2 +- gtsam/discrete/DiscreteBayesNet.h | 3 - gtsam/discrete/DiscreteBayesTree.h | 1 - gtsam/discrete/DiscreteFactor.h | 4 -- gtsam/discrete/DiscreteFactorGraph.h | 3 - gtsam/discrete/DiscreteLookupDAG.h | 3 - gtsam/discrete/SignatureParser.cpp | 4 +- gtsam/geometry/Cal3Bundler.cpp | 3 +- gtsam/geometry/Cal3DS2.cpp | 2 +- gtsam/geometry/Cal3DS2_Base.cpp | 6 +- gtsam/geometry/Cal3Fisheye.cpp | 6 +- gtsam/geometry/CalibratedCamera.h | 8 --- gtsam/geometry/PinholeCamera.h | 2 +- gtsam/geometry/PinholePose.h | 4 +- gtsam/geometry/StereoCamera.h | 2 +- gtsam/hybrid/HybridBayesTree.h | 2 - gtsam/hybrid/HybridFactor.h | 3 - gtsam/hybrid/HybridGaussianFactorGraph.cpp | 2 +- gtsam/hybrid/HybridValues.h | 24 ++++---- gtsam/hybrid/MixtureFactor.h | 2 - gtsam/inference/LabeledSymbol.cpp | 1 + gtsam/inference/Symbol.h | 2 +- gtsam/inference/VariableSlots.cpp | 1 + gtsam/linear/GaussianBayesNet.h | 3 - gtsam/linear/GaussianBayesTree.h | 1 - gtsam/linear/GaussianFactor.h | 2 +- gtsam/linear/GaussianFactorGraph.cpp | 4 +- gtsam/linear/GaussianFactorGraph.h | 2 +- gtsam/linear/HessianFactor.cpp | 2 +- gtsam/linear/NoiseModel.cpp | 2 +- gtsam/linear/NoiseModel.h | 2 +- gtsam/linear/PCGSolver.cpp | 2 +- gtsam/linear/VectorValues.cpp | 58 +++++++++++-------- gtsam/linear/linearExceptions.cpp | 8 +-- gtsam/linear/linearExceptions.h | 6 -- gtsam/navigation/BarometricFactor.h | 4 +- gtsam/navigation/CombinedImuFactor.h | 4 +- gtsam/navigation/NavState.cpp | 15 +++-- gtsam/nonlinear/CustomFactor.h | 2 - gtsam/nonlinear/DoglegOptimizer.cpp | 4 +- gtsam/nonlinear/ISAM2Clique.h | 1 - .../nonlinear/LevenbergMarquardtOptimizer.cpp | 3 +- gtsam/nonlinear/LevenbergMarquardtParams.h | 4 +- gtsam/nonlinear/NonlinearFactor.h | 2 +- gtsam/nonlinear/NonlinearFactorGraph.h | 2 +- .../internal/LevenbergMarquardtState.h | 18 +++--- gtsam/sfm/BinaryMeasurement.h | 3 - gtsam/sfm/DsfTrackGenerator.h | 4 +- gtsam/slam/FrobeniusFactor.cpp | 2 +- gtsam/slam/GeneralSFMFactor.h | 4 +- gtsam/slam/SmartProjectionRigFactor.h | 3 - gtsam/slam/dataset.cpp | 11 ++-- gtsam/symbolic/SymbolicBayesNet.h | 3 - gtsam/symbolic/SymbolicBayesTree.h | 1 - gtsam/symbolic/SymbolicFactor.h | 2 +- gtsam/symbolic/SymbolicFactorGraph.h | 3 - .../SmartProjectionPoseFactorRollingShutter.h | 3 - .../slam/SmartStereoProjectionFactorPP.h | 3 - .../slam/SmartStereoProjectionPoseFactor.h | 3 - 64 files changed, 126 insertions(+), 181 deletions(-) diff --git a/CppUnitLite/Test.h b/CppUnitLite/Test.h index 422427251a..040b812ded 100644 --- a/CppUnitLite/Test.h +++ b/CppUnitLite/Test.h @@ -32,7 +32,7 @@ class Test public: Test (const std::string& testName); Test (const std::string& testName, const std::string& filename, long lineNumber, bool safeCheck); - virtual ~Test() {}; + virtual ~Test() {} virtual void run (TestResult& result) = 0; @@ -63,7 +63,6 @@ class Test #define TEST(testGroup, testName)\ class testGroup##testName##Test : public Test \ { public: testGroup##testName##Test () : Test (#testName "Test", __FILE__, __LINE__, true) {} \ - virtual ~testGroup##testName##Test () {};\ void run (TestResult& result_) override;} \ testGroup##testName##Instance; \ void testGroup##testName##Test::run (TestResult& result_) diff --git a/CppUnitLite/TestResult.h b/CppUnitLite/TestResult.h index 3897d2990a..cae4921452 100644 --- a/CppUnitLite/TestResult.h +++ b/CppUnitLite/TestResult.h @@ -27,7 +27,7 @@ class TestResult { public: TestResult (); - virtual ~TestResult() {}; + virtual ~TestResult() {} virtual void testsStarted (); virtual void addFailure (const Failure& failure); virtual void testsEnded (); diff --git a/cmake/GtsamBuildTypes.cmake b/cmake/GtsamBuildTypes.cmake index cc3cbee6d2..3a2826ec6b 100644 --- a/cmake/GtsamBuildTypes.cmake +++ b/cmake/GtsamBuildTypes.cmake @@ -130,6 +130,8 @@ else() $<$:-Wreturn-local-addr -Werror=return-local-addr> # Error: return local address $<$:-Wreturn-stack-address -Werror=return-stack-address> # Error: return local address $<$:-Wno-misleading-indentation> # Eigen triggers a ton! + $<$:-Wno-weak-template-vtables> # TODO(dellaert): don't know how to resolve + $<$:-Wno-weak-vtables> # TODO(dellaert): don't know how to resolve -Wreturn-type -Werror=return-type # Error on missing return() -Wformat -Werror=format-security # Error on wrong printf() arguments $<$:${flag_override_}> # Enforce the use of the override keyword diff --git a/gtsam/base/DSFMap.h b/gtsam/base/DSFMap.h index c7ae09f20c..4bdebc7ecc 100644 --- a/gtsam/base/DSFMap.h +++ b/gtsam/base/DSFMap.h @@ -118,8 +118,8 @@ class IndexPair : public std::pair { public: inline IndexPair(): std::pair(0,0) {} inline IndexPair(size_t i, size_t j) : std::pair(i,j) {} - inline size_t i() const { return first; }; - inline size_t j() const { return second; }; + inline size_t i() const { return first; } + inline size_t j() const { return second; } }; typedef std::vector IndexPairVector; diff --git a/gtsam/base/concepts.h b/gtsam/base/concepts.h index 242e681da1..1649105cac 100644 --- a/gtsam/base/concepts.h +++ b/gtsam/base/concepts.h @@ -23,11 +23,11 @@ // These do something sensible: #define BOOST_CONCEPT_USAGE(concept) void check##concept() // TODO(dellaert): would be nice if it was a single macro... -#define GTSAM_CONCEPT_ASSERT(concept) concept checkConcept [[maybe_unused]]; -#define GTSAM_CONCEPT_ASSERT1(concept) concept checkConcept1 [[maybe_unused]]; -#define GTSAM_CONCEPT_ASSERT2(concept) concept checkConcept2 [[maybe_unused]]; -#define GTSAM_CONCEPT_ASSERT3(concept) concept checkConcept3 [[maybe_unused]]; -#define GTSAM_CONCEPT_ASSERT4(concept) concept checkConcept4 [[maybe_unused]]; +#define GTSAM_CONCEPT_ASSERT(concept) concept checkConcept [[maybe_unused]] +#define GTSAM_CONCEPT_ASSERT1(concept) concept checkConcept1 [[maybe_unused]] +#define GTSAM_CONCEPT_ASSERT2(concept) concept checkConcept2 [[maybe_unused]] +#define GTSAM_CONCEPT_ASSERT3(concept) concept checkConcept3 [[maybe_unused]] +#define GTSAM_CONCEPT_ASSERT4(concept) concept checkConcept4 [[maybe_unused]] // This one just ignores concept for now: #define GTSAM_CONCEPT_REQUIRES(concept, return_type) return_type #endif diff --git a/gtsam/base/types.cpp b/gtsam/base/types.cpp index 0abfc71ac1..83db14d0f7 100644 --- a/gtsam/base/types.cpp +++ b/gtsam/base/types.cpp @@ -42,7 +42,7 @@ std::string demangle(const char* name) { // g++ version of demangle char* demangled = nullptr; int status = -1; // some arbitrary value to eliminate the compiler warning - demangled = abi::__cxa_demangle(name, nullptr, nullptr, &status), + demangled = abi::__cxa_demangle(name, nullptr, nullptr, &status); demangled_name = (status == 0) ? std::string(demangled) : std::string(name); diff --git a/gtsam/discrete/DiscreteBayesNet.h b/gtsam/discrete/DiscreteBayesNet.h index 9005f975f7..a5a4621aa9 100644 --- a/gtsam/discrete/DiscreteBayesNet.h +++ b/gtsam/discrete/DiscreteBayesNet.h @@ -65,9 +65,6 @@ class GTSAM_EXPORT DiscreteBayesNet: public BayesNet { DiscreteBayesNet(const FactorGraph& graph) : Base(graph) {} - /// Destructor - virtual ~DiscreteBayesNet() {} - /// @} /// @name Testable diff --git a/gtsam/discrete/DiscreteBayesTree.h b/gtsam/discrete/DiscreteBayesTree.h index b0c3dfb7d8..e9b1325a0f 100644 --- a/gtsam/discrete/DiscreteBayesTree.h +++ b/gtsam/discrete/DiscreteBayesTree.h @@ -45,7 +45,6 @@ class GTSAM_EXPORT DiscreteBayesTreeClique typedef std::shared_ptr shared_ptr; typedef std::weak_ptr weak_ptr; DiscreteBayesTreeClique() {} - virtual ~DiscreteBayesTreeClique() {} DiscreteBayesTreeClique( const std::shared_ptr& conditional) : Base(conditional) {} diff --git a/gtsam/discrete/DiscreteFactor.h b/gtsam/discrete/DiscreteFactor.h index b026b1a3a9..f00ebc4993 100644 --- a/gtsam/discrete/DiscreteFactor.h +++ b/gtsam/discrete/DiscreteFactor.h @@ -59,10 +59,6 @@ class GTSAM_EXPORT DiscreteFactor: public Factor { template DiscreteFactor(const CONTAINER& keys) : Base(keys) {} - /// Virtual destructor - virtual ~DiscreteFactor() { - } - /// @} /// @name Testable /// @{ diff --git a/gtsam/discrete/DiscreteFactorGraph.h b/gtsam/discrete/DiscreteFactorGraph.h index d698a00c66..650fe7636f 100644 --- a/gtsam/discrete/DiscreteFactorGraph.h +++ b/gtsam/discrete/DiscreteFactorGraph.h @@ -111,9 +111,6 @@ class GTSAM_EXPORT DiscreteFactorGraph template DiscreteFactorGraph(const FactorGraph& graph) : Base(graph) {} - /// Destructor - virtual ~DiscreteFactorGraph() {} - /// @name Testable /// @{ diff --git a/gtsam/discrete/DiscreteLookupDAG.h b/gtsam/discrete/DiscreteLookupDAG.h index d3fd65ebe2..f077a13d9c 100644 --- a/gtsam/discrete/DiscreteLookupDAG.h +++ b/gtsam/discrete/DiscreteLookupDAG.h @@ -89,9 +89,6 @@ class GTSAM_EXPORT DiscreteLookupDAG : public BayesNet { /// Create from BayesNet with LookupTables static DiscreteLookupDAG FromBayesNet(const DiscreteBayesNet& bayesNet); - /// Destructor - virtual ~DiscreteLookupDAG() {} - /// @} /// @name Testable diff --git a/gtsam/discrete/SignatureParser.cpp b/gtsam/discrete/SignatureParser.cpp index 8e0221f015..31e4253925 100644 --- a/gtsam/discrete/SignatureParser.cpp +++ b/gtsam/discrete/SignatureParser.cpp @@ -38,7 +38,7 @@ std::optional static ParseConditional(const std::string& token) { } catch (...) { return std::nullopt; } - return row; + return std::move(row); } std::optional static ParseConditionalTable( @@ -62,7 +62,7 @@ std::optional
static ParseConditionalTable( } } } - return table; + return std::move(table); } std::vector static Tokenize(const std::string& str) { diff --git a/gtsam/geometry/Cal3Bundler.cpp b/gtsam/geometry/Cal3Bundler.cpp index cfaea61a9c..7e008aec35 100644 --- a/gtsam/geometry/Cal3Bundler.cpp +++ b/gtsam/geometry/Cal3Bundler.cpp @@ -113,7 +113,8 @@ Point2 Cal3Bundler::calibrate(const Point2& pi, OptionalJacobian<2, 3> Dcal, // Set px and py using intrinsic coordinates since that is where radial // distortion correction is done. - px = pn.x(), py = pn.y(); + px = pn.x(); + py = pn.y(); iteration++; } while (iteration < maxIterations); diff --git a/gtsam/geometry/Cal3DS2.cpp b/gtsam/geometry/Cal3DS2.cpp index f93386ea76..0295e22c91 100644 --- a/gtsam/geometry/Cal3DS2.cpp +++ b/gtsam/geometry/Cal3DS2.cpp @@ -31,7 +31,7 @@ std::ostream& operator<<(std::ostream& os, const Cal3DS2& cal) { } /* ************************************************************************* */ -void Cal3DS2::print(const std::string& s_) const { Base::print(s_); } +void Cal3DS2::print(const std::string& s) const { Base::print(s); } /* ************************************************************************* */ bool Cal3DS2::equals(const Cal3DS2& K, double tol) const { diff --git a/gtsam/geometry/Cal3DS2_Base.cpp b/gtsam/geometry/Cal3DS2_Base.cpp index a3f7026b93..b05728f053 100644 --- a/gtsam/geometry/Cal3DS2_Base.cpp +++ b/gtsam/geometry/Cal3DS2_Base.cpp @@ -40,9 +40,9 @@ std::ostream& operator<<(std::ostream& os, const Cal3DS2_Base& cal) { } /* ************************************************************************* */ -void Cal3DS2_Base::print(const std::string& s_) const { - gtsam::print((Matrix)K(), s_ + ".K"); - gtsam::print(Vector(k()), s_ + ".k"); +void Cal3DS2_Base::print(const std::string& s) const { + gtsam::print((Matrix)K(), s + ".K"); + gtsam::print(Vector(k()), s + ".k"); } /* ************************************************************************* */ diff --git a/gtsam/geometry/Cal3Fisheye.cpp b/gtsam/geometry/Cal3Fisheye.cpp index fac09e4650..357183b283 100644 --- a/gtsam/geometry/Cal3Fisheye.cpp +++ b/gtsam/geometry/Cal3Fisheye.cpp @@ -162,9 +162,9 @@ std::ostream& operator<<(std::ostream& os, const Cal3Fisheye& cal) { } /* ************************************************************************* */ -void Cal3Fisheye::print(const std::string& s_) const { - gtsam::print((Matrix)K(), s_ + ".K"); - gtsam::print(Vector(k()), s_ + ".k"); +void Cal3Fisheye::print(const std::string& s) const { + gtsam::print((Matrix)K(), s + ".K"); + gtsam::print(Vector(k()), s + ".k"); } /* ************************************************************************* */ diff --git a/gtsam/geometry/CalibratedCamera.h b/gtsam/geometry/CalibratedCamera.h index aa2ebd270c..dca15feb2c 100644 --- a/gtsam/geometry/CalibratedCamera.h +++ b/gtsam/geometry/CalibratedCamera.h @@ -308,14 +308,6 @@ class GTSAM_EXPORT CalibratedCamera: public PinholeBase { PinholeBase(v) { } - /// @} - /// @name Standard Interface - /// @{ - - /// destructor - virtual ~CalibratedCamera() { - } - /// @} /// @name Manifold /// @{ diff --git a/gtsam/geometry/PinholeCamera.h b/gtsam/geometry/PinholeCamera.h index 23b595c842..8329664fdf 100644 --- a/gtsam/geometry/PinholeCamera.h +++ b/gtsam/geometry/PinholeCamera.h @@ -321,7 +321,7 @@ class PinholeCamera: public PinholeBaseK { /// for Nonlinear Triangulation Vector defaultErrorWhenTriangulatingBehindCamera() const { - return Eigen::Matrix::dimension,1>::Constant(2.0 * K_.fx());; + return Eigen::Matrix::dimension,1>::Constant(2.0 * K_.fx()); } private: diff --git a/gtsam/geometry/PinholePose.h b/gtsam/geometry/PinholePose.h index 7670e1e888..92ae0f6fca 100644 --- a/gtsam/geometry/PinholePose.h +++ b/gtsam/geometry/PinholePose.h @@ -67,7 +67,7 @@ class PinholeBaseK: public PinholeBase { /// @name Standard Interface /// @{ - virtual ~PinholeBaseK() { + virtual ~PinholeBaseK() override { } /// return calibration @@ -425,7 +425,7 @@ class PinholePose: public PinholeBaseK { /// for Nonlinear Triangulation Vector defaultErrorWhenTriangulatingBehindCamera() const { - return Eigen::Matrix::dimension,1>::Constant(2.0 * K_->fx());; + return Eigen::Matrix::dimension,1>::Constant(2.0 * K_->fx()); } /// @} diff --git a/gtsam/geometry/StereoCamera.h b/gtsam/geometry/StereoCamera.h index 2a483ffcf1..da71dd0707 100644 --- a/gtsam/geometry/StereoCamera.h +++ b/gtsam/geometry/StereoCamera.h @@ -172,7 +172,7 @@ class GTSAM_EXPORT StereoCamera { /// for Nonlinear Triangulation Vector defaultErrorWhenTriangulatingBehindCamera() const { - return Eigen::Matrix::dimension,1>::Constant(2.0 * K_->fx());; + return Eigen::Matrix::dimension,1>::Constant(2.0 * K_->fx()); } /// @} diff --git a/gtsam/hybrid/HybridBayesTree.h b/gtsam/hybrid/HybridBayesTree.h index e0e6db98ec..bc2a0f852a 100644 --- a/gtsam/hybrid/HybridBayesTree.h +++ b/gtsam/hybrid/HybridBayesTree.h @@ -55,8 +55,6 @@ class GTSAM_EXPORT HybridBayesTreeClique : Base(conditional) {} ///< Copy constructor HybridBayesTreeClique(const HybridBayesTreeClique& clique) : Base(clique) {} - - virtual ~HybridBayesTreeClique() {} }; /* ************************************************************************* */ diff --git a/gtsam/hybrid/HybridFactor.h b/gtsam/hybrid/HybridFactor.h index 8fa23b1f96..13d5c2cba3 100644 --- a/gtsam/hybrid/HybridFactor.h +++ b/gtsam/hybrid/HybridFactor.h @@ -97,9 +97,6 @@ class GTSAM_EXPORT HybridFactor : public Factor { HybridFactor(const KeyVector &continuousKeys, const DiscreteKeys &discreteKeys); - /// Virtual destructor - virtual ~HybridFactor() = default; - /// @} /// @name Testable /// @{ diff --git a/gtsam/hybrid/HybridGaussianFactorGraph.cpp b/gtsam/hybrid/HybridGaussianFactorGraph.cpp index a8c674dec5..3d4fe72b82 100644 --- a/gtsam/hybrid/HybridGaussianFactorGraph.cpp +++ b/gtsam/hybrid/HybridGaussianFactorGraph.cpp @@ -287,7 +287,7 @@ hybridElimination(const HybridGaussianFactorGraph &factors, auto hf = std::dynamic_pointer_cast(factor); if (!hf) throw std::runtime_error("Expected HessianFactor!"); hf->constantTerm() += 2.0 * pair.first->logNormalizationConstant(); - return hf; + return std::move(hf); }; GaussianMixtureFactor::Factors correctedFactors(eliminationResults, diff --git a/gtsam/hybrid/HybridValues.h b/gtsam/hybrid/HybridValues.h index 94365db75a..40d4b5e92a 100644 --- a/gtsam/hybrid/HybridValues.h +++ b/gtsam/hybrid/HybridValues.h @@ -54,13 +54,13 @@ class GTSAM_EXPORT HybridValues { HybridValues() = default; /// Construct from DiscreteValues and VectorValues. - HybridValues(const VectorValues& cv, const DiscreteValues& dv) - : continuous_(cv), discrete_(dv){}; + HybridValues(const VectorValues &cv, const DiscreteValues &dv) + : continuous_(cv), discrete_(dv){} /// Construct from all values types. HybridValues(const VectorValues& cv, const DiscreteValues& dv, const Values& v) - : continuous_(cv), discrete_(dv), nonlinear_(v){}; + : continuous_(cv), discrete_(dv), nonlinear_(v){} /// @} /// @name Testable @@ -73,7 +73,7 @@ class GTSAM_EXPORT HybridValues { continuous_.print(" Continuous", keyFormatter); // print continuous components discrete_.print(" Discrete", keyFormatter); // print discrete components - }; + } /// equals required by Testable for unit testing bool equals(const HybridValues& other, double tol = 1e-9) const { @@ -95,20 +95,20 @@ class GTSAM_EXPORT HybridValues { const Values& nonlinear() const { return nonlinear_; } /// Check whether a variable with key \c j exists in VectorValues. - bool existsVector(Key j) { return continuous_.exists(j); }; + bool existsVector(Key j) { return continuous_.exists(j); } /// Check whether a variable with key \c j exists in DiscreteValues. - bool existsDiscrete(Key j) { return (discrete_.find(j) != discrete_.end()); }; + bool existsDiscrete(Key j) { return (discrete_.find(j) != discrete_.end()); } /// Check whether a variable with key \c j exists in values. bool existsNonlinear(Key j) { return nonlinear_.exists(j); - }; + } /// Check whether a variable with key \c j exists. bool exists(Key j) { return existsVector(j) || existsDiscrete(j) || existsNonlinear(j); - }; + } /** Insert a vector \c value with key \c j. Throws an invalid_argument * exception if the key \c j is already used. @@ -120,7 +120,7 @@ class GTSAM_EXPORT HybridValues { * the key \c j is already used. * @param value The vector to be inserted. * @param j The index with which the value will be associated. */ - void insert(Key j, size_t value) { discrete_[j] = value; }; + void insert(Key j, size_t value) { discrete_[j] = value; } /// insert_or_assign() , similar to Values.h void insert_or_assign(Key j, const Vector& value) { @@ -166,13 +166,13 @@ class GTSAM_EXPORT HybridValues { * Read/write access to the vector value with key \c j, throws * std::out_of_range if \c j does not exist. */ - Vector& at(Key j) { return continuous_.at(j); }; + Vector& at(Key j) { return continuous_.at(j); } /** * Read/write access to the discrete value with key \c j, throws * std::out_of_range if \c j does not exist. */ - size_t& atDiscrete(Key j) { return discrete_.at(j); }; + size_t& atDiscrete(Key j) { return discrete_.at(j); } /** For all key/value pairs in \c values, replace continuous values with * corresponding keys in this object with those in \c values. Throws @@ -227,7 +227,7 @@ class GTSAM_EXPORT HybridValues { ss << this->continuous_.html(keyFormatter); ss << this->discrete_.html(keyFormatter); return ss.str(); - }; + } /// @} }; diff --git a/gtsam/hybrid/MixtureFactor.h b/gtsam/hybrid/MixtureFactor.h index cc0a304a21..df8e0193ad 100644 --- a/gtsam/hybrid/MixtureFactor.h +++ b/gtsam/hybrid/MixtureFactor.h @@ -123,8 +123,6 @@ class MixtureFactor : public HybridFactor { } } - ~MixtureFactor() = default; - /** * @brief Compute error of the MixtureFactor as a tree. * diff --git a/gtsam/inference/LabeledSymbol.cpp b/gtsam/inference/LabeledSymbol.cpp index c187e864ee..26c30a35c4 100644 --- a/gtsam/inference/LabeledSymbol.cpp +++ b/gtsam/inference/LabeledSymbol.cpp @@ -18,6 +18,7 @@ #include #include +#include namespace gtsam { diff --git a/gtsam/inference/Symbol.h b/gtsam/inference/Symbol.h index 6ae5188cf7..9f21337076 100644 --- a/gtsam/inference/Symbol.h +++ b/gtsam/inference/Symbol.h @@ -85,7 +85,7 @@ class GTSAM_EXPORT Symbol { operator std::string() const; /// Return string representation of the key - std::string string() const { return std::string(*this); }; + std::string string() const { return std::string(*this); } /** Comparison for use in maps */ bool operator<(const Symbol& comp) const { diff --git a/gtsam/inference/VariableSlots.cpp b/gtsam/inference/VariableSlots.cpp index 64883fe49a..d108eae39f 100644 --- a/gtsam/inference/VariableSlots.cpp +++ b/gtsam/inference/VariableSlots.cpp @@ -18,6 +18,7 @@ #include #include +#include using namespace std; diff --git a/gtsam/linear/GaussianBayesNet.h b/gtsam/linear/GaussianBayesNet.h index 39528b810a..19781d1e6d 100644 --- a/gtsam/linear/GaussianBayesNet.h +++ b/gtsam/linear/GaussianBayesNet.h @@ -74,9 +74,6 @@ namespace gtsam { std::initializer_list > conditionals) : Base(conditionals) {} - /// Destructor - virtual ~GaussianBayesNet() = default; - /// @} /// @name Testable diff --git a/gtsam/linear/GaussianBayesTree.h b/gtsam/linear/GaussianBayesTree.h index 3039960c23..4ab0e7b905 100644 --- a/gtsam/linear/GaussianBayesTree.h +++ b/gtsam/linear/GaussianBayesTree.h @@ -41,7 +41,6 @@ namespace gtsam { typedef std::shared_ptr shared_ptr; typedef std::weak_ptr weak_ptr; GaussianBayesTreeClique() {} - virtual ~GaussianBayesTreeClique() {} GaussianBayesTreeClique(const std::shared_ptr& conditional) : Base(conditional) {} }; diff --git a/gtsam/linear/GaussianFactor.h b/gtsam/linear/GaussianFactor.h index 3304829e20..3441861e21 100644 --- a/gtsam/linear/GaussianFactor.h +++ b/gtsam/linear/GaussianFactor.h @@ -51,7 +51,7 @@ namespace gtsam { GaussianFactor(const CONTAINER& keys) : Base(keys) {} /** Destructor */ - virtual ~GaussianFactor() {} + virtual ~GaussianFactor() override {} // Implementing Testable interface diff --git a/gtsam/linear/GaussianFactorGraph.cpp b/gtsam/linear/GaussianFactorGraph.cpp index f879ea0f66..cb42f0a2fe 100644 --- a/gtsam/linear/GaussianFactorGraph.cpp +++ b/gtsam/linear/GaussianFactorGraph.cpp @@ -249,7 +249,7 @@ namespace gtsam { // combine all factors and get upper-triangular part of Hessian Scatter scatter(*this, ordering); HessianFactor combined(*this, scatter); - return combined.info().selfadjointView();; + return combined.info().selfadjointView(); } /* ************************************************************************* */ @@ -257,7 +257,7 @@ namespace gtsam { // combine all factors and get upper-triangular part of Hessian Scatter scatter(*this); HessianFactor combined(*this, scatter); - return combined.info().selfadjointView();; + return combined.info().selfadjointView(); } /* ************************************************************************* */ diff --git a/gtsam/linear/GaussianFactorGraph.h b/gtsam/linear/GaussianFactorGraph.h index d517de77b9..96122eb6be 100644 --- a/gtsam/linear/GaussianFactorGraph.h +++ b/gtsam/linear/GaussianFactorGraph.h @@ -108,7 +108,7 @@ namespace gtsam { GaussianFactorGraph(const FactorGraph& graph) : Base(graph) {} /** Virtual destructor */ - virtual ~GaussianFactorGraph() {} + virtual ~GaussianFactorGraph() override {} /// @} /// @name Testable diff --git a/gtsam/linear/HessianFactor.cpp b/gtsam/linear/HessianFactor.cpp index db943aa70b..3765090699 100644 --- a/gtsam/linear/HessianFactor.cpp +++ b/gtsam/linear/HessianFactor.cpp @@ -378,7 +378,7 @@ GaussianFactor::shared_ptr HessianFactor::negate() const { shared_ptr result = std::make_shared(*this); // Negate the information matrix of the result result->info_.negate(); - return result; + return std::move(result); } /* ************************************************************************* */ diff --git a/gtsam/linear/NoiseModel.cpp b/gtsam/linear/NoiseModel.cpp index 2751e89f2f..7ea8e5a546 100644 --- a/gtsam/linear/NoiseModel.cpp +++ b/gtsam/linear/NoiseModel.cpp @@ -63,7 +63,7 @@ std::optional checkIfDiagonal(const Matrix& M) { Vector diagonal(n); for (j = 0; j < n; j++) diagonal(j) = M(j, j); - return diagonal; + return std::move(diagonal); } } diff --git a/gtsam/linear/NoiseModel.h b/gtsam/linear/NoiseModel.h index 72069f9f46..489f11e4c2 100644 --- a/gtsam/linear/NoiseModel.h +++ b/gtsam/linear/NoiseModel.h @@ -668,7 +668,7 @@ namespace gtsam { public: /// Default Constructor for serialization - Robust() {}; + Robust() {} /// Constructor Robust(const RobustModel::shared_ptr robust, const NoiseModel::shared_ptr noise) diff --git a/gtsam/linear/PCGSolver.cpp b/gtsam/linear/PCGSolver.cpp index cc461e63cf..5ec6fa67bd 100644 --- a/gtsam/linear/PCGSolver.cpp +++ b/gtsam/linear/PCGSolver.cpp @@ -48,7 +48,7 @@ void PCGSolverParameters::setPreconditionerParams(const std::shared_ptr -using namespace std; +#include +#include + +// assert_throw needs a semicolon in Release mode. +#pragma clang diagnostic push +#pragma clang diagnostic ignored "-Wextra-semi-stmt" namespace gtsam { @@ -27,10 +32,10 @@ namespace gtsam { { // Merge using predicate for comparing first of pair merge(first.begin(), first.end(), second.begin(), second.end(), inserter(values_, values_.end()), - std::bind(&less::operator(), less(), std::bind(&KeyValuePair::first, std::placeholders::_1), + std::bind(&std::less::operator(), std::less(), std::bind(&KeyValuePair::first, std::placeholders::_1), std::bind(&KeyValuePair::first, std::placeholders::_2))); if(size() != first.size() + second.size()) - throw invalid_argument("Requested to merge two VectorValues that have one or more variables in common."); + throw std::invalid_argument("Requested to merge two VectorValues that have one or more variables in common."); } /* ************************************************************************ */ @@ -92,7 +97,7 @@ namespace gtsam { hint = values_.insert(hint, {key, value}); if (values_.size() > oldSize) { values_.unsafe_erase(hint); - throw out_of_range( + throw std::out_of_range( "Requested to update a VectorValues with another VectorValues that " "contains keys not present in the first."); } else { @@ -107,7 +112,7 @@ namespace gtsam { size_t originalSize = size(); values_.insert(values.begin(), values.end()); if (size() != originalSize + values.size()) - throw invalid_argument( + throw std::invalid_argument( "Requested to insert a VectorValues into another VectorValues that " "already contains one or more of its keys."); return *this; @@ -122,7 +127,7 @@ namespace gtsam { } /* ************************************************************************ */ - GTSAM_EXPORT ostream& operator<<(ostream& os, const VectorValues& v) { + GTSAM_EXPORT std::ostream& operator<<(std::ostream& os, const VectorValues& v) { // Change print depending on whether we are using TBB #ifdef GTSAM_USE_TBB map sorted; @@ -140,11 +145,11 @@ namespace gtsam { } /* ************************************************************************ */ - void VectorValues::print(const string& str, + void VectorValues::print(const std::string& str, const KeyFormatter& formatter) const { - cout << str << ": " << size() << " elements\n"; - cout << key_formatter(formatter) << *this; - cout.flush(); + std::cout << str << ": " << size() << " elements\n"; + std::cout << key_formatter(formatter) << *this; + std::cout.flush(); } /* ************************************************************************ */ @@ -222,15 +227,15 @@ namespace gtsam { double VectorValues::dot(const VectorValues& v) const { if(this->size() != v.size()) - throw invalid_argument("VectorValues::dot called with a VectorValues of different structure"); + throw std::invalid_argument("VectorValues::dot called with a VectorValues of different structure"); double result = 0.0; auto this_it = this->begin(); auto v_it = v.begin(); for(; this_it != this->end(); ++this_it, ++v_it) { assert_throw(this_it->first == v_it->first, - invalid_argument("VectorValues::dot called with a VectorValues of different structure")); + std::invalid_argument("VectorValues::dot called with a VectorValues of different structure")); assert_throw(this_it->second.size() == v_it->second.size(), - invalid_argument("VectorValues::dot called with a VectorValues of different structure")); + std::invalid_argument("VectorValues::dot called with a VectorValues of different structure")); result += this_it->second.dot(v_it->second); } return result; @@ -254,9 +259,9 @@ namespace gtsam { VectorValues VectorValues::operator+(const VectorValues& c) const { if(this->size() != c.size()) - throw invalid_argument("VectorValues::operator+ called with different vector sizes"); + throw std::invalid_argument("VectorValues::operator+ called with different vector sizes"); assert_throw(hasSameStructure(c), - invalid_argument("VectorValues::operator+ called with different vector sizes")); + std::invalid_argument("VectorValues::operator+ called with different vector sizes")); VectorValues result; // The result.end() hint here should result in constant-time inserts @@ -280,9 +285,9 @@ namespace gtsam { VectorValues& VectorValues::operator+=(const VectorValues& c) { if(this->size() != c.size()) - throw invalid_argument("VectorValues::operator+= called with different vector sizes"); + throw std::invalid_argument("VectorValues::operator+= called with different vector sizes"); assert_throw(hasSameStructure(c), - invalid_argument("VectorValues::operator+= called with different vector sizes")); + std::invalid_argument("VectorValues::operator+= called with different vector sizes")); iterator j1 = begin(); const_iterator j2 = c.begin(); @@ -303,11 +308,11 @@ namespace gtsam { VectorValues& VectorValues::addInPlace_(const VectorValues& c) { for(const_iterator j2 = c.begin(); j2 != c.end(); ++j2) { - pair xi = tryInsert(j2->first, Vector()); - if(xi.second) - xi.first->second = j2->second; + const auto& [it, success] = tryInsert(j2->first, Vector()); + if(success) + it->second = j2->second; else - xi.first->second += j2->second; + it->second += j2->second; } return *this; } @@ -316,9 +321,9 @@ namespace gtsam { VectorValues VectorValues::operator-(const VectorValues& c) const { if(this->size() != c.size()) - throw invalid_argument("VectorValues::operator- called with different vector sizes"); + throw std::invalid_argument("VectorValues::operator- called with different vector sizes"); assert_throw(hasSameStructure(c), - invalid_argument("VectorValues::operator- called with different vector sizes")); + std::invalid_argument("VectorValues::operator- called with different vector sizes")); VectorValues result; // The result.end() hint here should result in constant-time inserts @@ -373,8 +378,8 @@ namespace gtsam { } /* ************************************************************************ */ - string VectorValues::html(const KeyFormatter& keyFormatter) const { - stringstream ss; + std::string VectorValues::html(const KeyFormatter& keyFormatter) const { + std::stringstream ss; // Print out preamble. ss << "
\n
\n \n"; @@ -406,3 +411,6 @@ namespace gtsam { /* ************************************************************************ */ } // \namespace gtsam + +#pragma clang diagnostic pop + diff --git a/gtsam/linear/linearExceptions.cpp b/gtsam/linear/linearExceptions.cpp index 75f284348c..4e6b789a6f 100644 --- a/gtsam/linear/linearExceptions.cpp +++ b/gtsam/linear/linearExceptions.cpp @@ -41,23 +41,23 @@ more information."); /* ************************************************************************* */ const char* InvalidNoiseModel::what() const noexcept { - if(description_.empty()) + if(description_->empty()) description_ = "A JacobianFactor was attempted to be constructed or modified to use a\n" "noise model of incompatible dimension. The JacobianFactor has\n" "dimensionality (i.e. length of error vector) " + std::to_string(factorDims) + " but the provided noise model has dimensionality " + std::to_string(noiseModelDims) + "."; - return description_.c_str(); + return description_->c_str(); } /* ************************************************************************* */ const char* InvalidMatrixBlock::what() const noexcept { - if(description_.empty()) { + if(description_->empty()) { description_ = "A JacobianFactor was attempted to be constructed with a matrix block of\n" "inconsistent dimension. The JacobianFactor has " + std::to_string(factorRows) + " rows (i.e. length of error vector) but the provided matrix block has " + std::to_string(blockRows) + " rows."; } - return description_.c_str(); + return description_->c_str(); } } diff --git a/gtsam/linear/linearExceptions.h b/gtsam/linear/linearExceptions.h index 72981613e5..c412429aaf 100644 --- a/gtsam/linear/linearExceptions.h +++ b/gtsam/linear/linearExceptions.h @@ -113,9 +113,6 @@ namespace gtsam { ~InvalidNoiseModel() noexcept override {} const char* what() const noexcept override; - - private: - mutable std::string description_; }; /* ************************************************************************* */ @@ -131,9 +128,6 @@ namespace gtsam { ~InvalidMatrixBlock() noexcept override {} const char* what() const noexcept override; - - private: - mutable std::string description_; }; /* ************************************************************************* */ diff --git a/gtsam/navigation/BarometricFactor.h b/gtsam/navigation/BarometricFactor.h index cf1c147bfc..38677ed589 100644 --- a/gtsam/navigation/BarometricFactor.h +++ b/gtsam/navigation/BarometricFactor.h @@ -89,12 +89,12 @@ class GTSAM_EXPORT BarometricFactor : public NoiseModelFactorN { // From https://www.grc.nasa.gov/www/k-12/airplane/atmosmet.html return (std::pow(n / 101.29, 1. / 5.256) * 288.08 - 273.1 - 15.04) / -0.00649; - }; + } inline double baroOut(const double& meters) { double temp = 15.04 - 0.00649 * meters; return 101.29 * std::pow(((temp + 273.1) / 288.08), 5.256); - }; + } private: #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION /// diff --git a/gtsam/navigation/CombinedImuFactor.h b/gtsam/navigation/CombinedImuFactor.h index dc0866045a..2910fc76b2 100644 --- a/gtsam/navigation/CombinedImuFactor.h +++ b/gtsam/navigation/CombinedImuFactor.h @@ -71,8 +71,8 @@ struct GTSAM_EXPORT PreintegrationCombinedParams : PreintegrationParams { biasAccOmegaInt(I_6x6) {} /// See two named constructors below for good values of n_gravity in body frame - PreintegrationCombinedParams(const Vector3& n_gravity) : - PreintegrationParams(n_gravity), biasAccCovariance(I_3x3), + PreintegrationCombinedParams(const Vector3& _n_gravity) : + PreintegrationParams(_n_gravity), biasAccCovariance(I_3x3), biasOmegaCovariance(I_3x3), biasAccOmegaInt(I_6x6) { } diff --git a/gtsam/navigation/NavState.cpp b/gtsam/navigation/NavState.cpp index 86e85a7627..6a17e9ea05 100644 --- a/gtsam/navigation/NavState.cpp +++ b/gtsam/navigation/NavState.cpp @@ -18,12 +18,10 @@ #include -using namespace std; +#include namespace gtsam { -#define TIE(R,t,v,x) const Rot3& R = (x).R_;const Point3& t = (x).t_;const Velocity3& v = (x).v_; - //------------------------------------------------------------------------------ NavState NavState::Create(const Rot3& R, const Point3& t, const Velocity3& v, OptionalJacobian<9, 3> H1, OptionalJacobian<9, 3> H2, @@ -87,7 +85,7 @@ Matrix7 NavState::matrix() const { } //------------------------------------------------------------------------------ -ostream& operator<<(ostream& os, const NavState& state) { +std::ostream& operator<<(std::ostream& os, const NavState& state) { os << "R: " << state.attitude() << "\n"; os << "p: " << state.position().transpose() << "\n"; os << "v: " << state.velocity().transpose(); @@ -95,8 +93,8 @@ ostream& operator<<(ostream& os, const NavState& state) { } //------------------------------------------------------------------------------ -void NavState::print(const string& s) const { - cout << (s.empty() ? s : s + " ") << *this << endl; +void NavState::print(const std::string& s) const { + std::cout << (s.empty() ? s : s + " ") << *this << std::endl; } //------------------------------------------------------------------------------ @@ -108,7 +106,7 @@ bool NavState::equals(const NavState& other, double tol) const { //------------------------------------------------------------------------------ NavState NavState::retract(const Vector9& xi, // OptionalJacobian<9, 9> H1, OptionalJacobian<9, 9> H2) const { - TIE(nRb, n_t, n_v, *this); + auto [nRb, n_t, n_v] = (*this); Matrix3 D_bRc_xi, D_R_nRb, D_t_nRb, D_v_nRb; const Rot3 bRc = Rot3::Expmap(dR(xi), H2 ? &D_bRc_xi : 0); const Rot3 nRc = nRb.compose(bRc, H1 ? &D_R_nRb : 0); @@ -214,7 +212,8 @@ NavState NavState::update(const Vector3& b_acceleration, const Vector3& b_omega, //------------------------------------------------------------------------------ Vector9 NavState::coriolis(double dt, const Vector3& omega, bool secondOrder, OptionalJacobian<9, 9> H) const { - TIE(nRb, n_t, n_v, *this); + auto [nRb, n_t, n_v] = (*this); + const double dt2 = dt * dt; const Vector3 omega_cross_vel = omega.cross(n_v); diff --git a/gtsam/nonlinear/CustomFactor.h b/gtsam/nonlinear/CustomFactor.h index d486e6f0db..ac29420320 100644 --- a/gtsam/nonlinear/CustomFactor.h +++ b/gtsam/nonlinear/CustomFactor.h @@ -69,8 +69,6 @@ class CustomFactor: public NoiseModelFactor { this->error_function_ = errorFunction; } - ~CustomFactor() override = default; - /** * Calls the errorFunction closure, which is a std::function object * One can check if a derivative is needed in the errorFunction by checking the length of Jacobian array diff --git a/gtsam/nonlinear/DoglegOptimizer.cpp b/gtsam/nonlinear/DoglegOptimizer.cpp index 8899685dee..a34000a322 100644 --- a/gtsam/nonlinear/DoglegOptimizer.cpp +++ b/gtsam/nonlinear/DoglegOptimizer.cpp @@ -54,8 +54,8 @@ namespace internal { struct DoglegState : public NonlinearOptimizerState { const double delta; - DoglegState(const Values& values, double error, double delta, unsigned int iterations = 0) - : NonlinearOptimizerState(values, error, iterations), delta(delta) {} + DoglegState(const Values& _values, double _error, double _delta, unsigned int _iterations = 0) + : NonlinearOptimizerState(_values, _error, _iterations), delta(_delta) {} }; } diff --git a/gtsam/nonlinear/ISAM2Clique.h b/gtsam/nonlinear/ISAM2Clique.h index 08b74ef261..fde9dd3f2d 100644 --- a/gtsam/nonlinear/ISAM2Clique.h +++ b/gtsam/nonlinear/ISAM2Clique.h @@ -51,7 +51,6 @@ class GTSAM_EXPORT ISAM2Clique /// Default constructor ISAM2Clique() : Base() {} - virtual ~ISAM2Clique() = default; /// Copy constructor, does *not* copy solution pointers as these are invalid /// in different trees. diff --git a/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp b/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp index 922ba91290..c49e3a65a3 100644 --- a/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp +++ b/gtsam/nonlinear/LevenbergMarquardtOptimizer.cpp @@ -145,7 +145,8 @@ bool LevenbergMarquardtOptimizer::tryLambda(const GaussianFactorGraph& linear, double modelFidelity = 0.0; bool step_is_successful = false; bool stopSearchingLambda = false; - double newError = numeric_limits::infinity(), costChange; + double newError = numeric_limits::infinity(); + double costChange = 0.0; Values newValues; VectorValues delta; diff --git a/gtsam/nonlinear/LevenbergMarquardtParams.h b/gtsam/nonlinear/LevenbergMarquardtParams.h index d7046654eb..b2eae36215 100644 --- a/gtsam/nonlinear/LevenbergMarquardtParams.h +++ b/gtsam/nonlinear/LevenbergMarquardtParams.h @@ -117,8 +117,8 @@ class GTSAM_EXPORT LevenbergMarquardtParams: public NonlinearOptimizerParams { } static LevenbergMarquardtParams ReplaceOrdering(LevenbergMarquardtParams params, - const Ordering& ordering) { - params.ordering = ordering; + const Ordering& ord) { + params.ordering = ord; return params; } diff --git a/gtsam/nonlinear/NonlinearFactor.h b/gtsam/nonlinear/NonlinearFactor.h index e8ae9fd47c..c2e246add3 100644 --- a/gtsam/nonlinear/NonlinearFactor.h +++ b/gtsam/nonlinear/NonlinearFactor.h @@ -106,7 +106,7 @@ class GTSAM_EXPORT NonlinearFactor: public Factor { /// @{ /** Destructor */ - virtual ~NonlinearFactor() {} + virtual ~NonlinearFactor() override {} /** * In nonlinear factors, the error function returns the negative log-likelihood diff --git a/gtsam/nonlinear/NonlinearFactorGraph.h b/gtsam/nonlinear/NonlinearFactorGraph.h index cf25657257..d4d3ea4881 100644 --- a/gtsam/nonlinear/NonlinearFactorGraph.h +++ b/gtsam/nonlinear/NonlinearFactorGraph.h @@ -79,7 +79,7 @@ namespace gtsam { NonlinearFactorGraph(const FactorGraph& graph) : Base(graph) {} /// Destructor - virtual ~NonlinearFactorGraph() {} + virtual ~NonlinearFactorGraph() override {} /// @} /// @name Testable diff --git a/gtsam/nonlinear/internal/LevenbergMarquardtState.h b/gtsam/nonlinear/internal/LevenbergMarquardtState.h index be1afc9723..696c654805 100644 --- a/gtsam/nonlinear/internal/LevenbergMarquardtState.h +++ b/gtsam/nonlinear/internal/LevenbergMarquardtState.h @@ -49,19 +49,19 @@ struct LevenbergMarquardtState : public NonlinearOptimizerState { // optimization (for each iteration, LM tries multiple // inner iterations with different lambdas) - LevenbergMarquardtState(const Values& initialValues, double error, double lambda, - double currentFactor, unsigned int iterations = 0, + LevenbergMarquardtState(const Values& initialValues, double _error, double _lambda, + double currentFactor, unsigned int _iterations = 0, unsigned int totalNumberInnerIterations = 0) - : NonlinearOptimizerState(initialValues, error, iterations), - lambda(lambda), + : NonlinearOptimizerState(initialValues, _error, _iterations), + lambda(_lambda), currentFactor(currentFactor), totalNumberInnerIterations(totalNumberInnerIterations) {} // Constructor version that takes ownership of values - LevenbergMarquardtState(Values&& initialValues, double error, double lambda, double currentFactor, - unsigned int iterations = 0, unsigned int totalNumberInnerIterations = 0) - : NonlinearOptimizerState(initialValues, error, iterations), - lambda(lambda), + LevenbergMarquardtState(Values&& initialValues, double _error, double _lambda, double currentFactor, + unsigned int _iterations = 0, unsigned int totalNumberInnerIterations = 0) + : NonlinearOptimizerState(initialValues, _error, _iterations), + lambda(_lambda), currentFactor(currentFactor), totalNumberInnerIterations(totalNumberInnerIterations) {} @@ -119,7 +119,7 @@ struct LevenbergMarquardtState : public NonlinearOptimizerState { if (!item->model) *item = CachedModel(dim, 1.0 / std::sqrt(lambda)); return item; - }; + } /// Build a damped system for a specific lambda, vanilla version GaussianFactorGraph buildDampedSystem(GaussianFactorGraph damped /* gets copied */) const { diff --git a/gtsam/sfm/BinaryMeasurement.h b/gtsam/sfm/BinaryMeasurement.h index debb27bc15..07aa2e3a5f 100644 --- a/gtsam/sfm/BinaryMeasurement.h +++ b/gtsam/sfm/BinaryMeasurement.h @@ -52,9 +52,6 @@ template class BinaryMeasurement : public Factor { measured_(measured), noiseModel_(model) {} - /// Destructor - virtual ~BinaryMeasurement() {} - /// @name Standard Interface /// @{ diff --git a/gtsam/sfm/DsfTrackGenerator.h b/gtsam/sfm/DsfTrackGenerator.h index 518a5d10b8..27cfdfa2ba 100644 --- a/gtsam/sfm/DsfTrackGenerator.h +++ b/gtsam/sfm/DsfTrackGenerator.h @@ -48,8 +48,8 @@ struct Keypoints { /// Optional confidences/responses for each detection, of shape N. std::optional responses; - Keypoints(const Eigen::MatrixX2d& coordinates) - : coordinates(coordinates){}; // std::nullopt + Keypoints(const Eigen::MatrixX2d &_coordinates) + : coordinates(_coordinates) {} }; using KeypointsVector = std::vector; diff --git a/gtsam/slam/FrobeniusFactor.cpp b/gtsam/slam/FrobeniusFactor.cpp index 982430d81e..e70f64d969 100644 --- a/gtsam/slam/FrobeniusFactor.cpp +++ b/gtsam/slam/FrobeniusFactor.cpp @@ -61,7 +61,7 @@ ConvertNoiseModel(const SharedNoiseModel &model, size_t d, bool defaultToUnit) { return noiseModel::Robust::Create( noiseModel::mEstimator::Huber::Create(1.345), isoModel); } else { - return isoModel; + return std::move(isoModel); } } diff --git a/gtsam/slam/GeneralSFMFactor.h b/gtsam/slam/GeneralSFMFactor.h index 763f3666dc..581624b389 100644 --- a/gtsam/slam/GeneralSFMFactor.h +++ b/gtsam/slam/GeneralSFMFactor.h @@ -129,7 +129,7 @@ class GeneralSFMFactor: public NoiseModelFactorN { try { return camera.project2(point,H1,H2) - measured_; } - catch( CheiralityException& e) { + catch( CheiralityException& e [[maybe_unused]]) { if (H1) *H1 = JacobianC::Zero(); if (H2) *H2 = JacobianL::Zero(); //TODO Print the exception via logging @@ -150,7 +150,7 @@ class GeneralSFMFactor: public NoiseModelFactorN { const CAMERA& camera = values.at(key1); const LANDMARK& point = values.at(key2); b = measured() - camera.project2(point, H1, H2); - } catch (CheiralityException& e) { + } catch (CheiralityException& e [[maybe_unused]]) { H1.setZero(); H2.setZero(); b.setZero(); diff --git a/gtsam/slam/SmartProjectionRigFactor.h b/gtsam/slam/SmartProjectionRigFactor.h index 0aa070ed08..6007c84e25 100644 --- a/gtsam/slam/SmartProjectionRigFactor.h +++ b/gtsam/slam/SmartProjectionRigFactor.h @@ -107,9 +107,6 @@ class SmartProjectionRigFactor : public SmartProjectionFactor { "linearizationMode must be set to HESSIAN"); } - /** Virtual destructor */ - ~SmartProjectionRigFactor() override = default; - /** * add a new measurement, corresponding to an observation from pose "poseKey" * and taken from the camera in the rig identified by "cameraId" diff --git a/gtsam/slam/dataset.cpp b/gtsam/slam/dataset.cpp index b5b8303fb9..91317bad1e 100644 --- a/gtsam/slam/dataset.cpp +++ b/gtsam/slam/dataset.cpp @@ -456,19 +456,14 @@ template <> struct ParseMeasurement { // The actual parser std::optional> operator()(std::istream &is, const std::string &tag) { - if (tag != "BR" && tag != "LANDMARK") - return std::nullopt; - size_t id1, id2; is >> id1 >> id2; double bearing, range, bearing_std, range_std; if (tag == "BR") { is >> bearing >> range >> bearing_std >> range_std; - } - - // A landmark measurement, converted to bearing-range - if (tag == "LANDMARK") { + } else if (tag == "LANDMARK") { + // A landmark measurement, converted to bearing-range double lmx, lmy; double v1, v2, v3; @@ -489,6 +484,8 @@ template <> struct ParseMeasurement { bearing_std = 1; range_std = 1; } + } else { + return std::nullopt; } // optional filter diff --git a/gtsam/symbolic/SymbolicBayesNet.h b/gtsam/symbolic/SymbolicBayesNet.h index bbfc968e16..3102191dcc 100644 --- a/gtsam/symbolic/SymbolicBayesNet.h +++ b/gtsam/symbolic/SymbolicBayesNet.h @@ -83,9 +83,6 @@ namespace gtsam { return *this; } - /// Destructor - virtual ~SymbolicBayesNet() {} - /// @} /// @name Testable diff --git a/gtsam/symbolic/SymbolicBayesTree.h b/gtsam/symbolic/SymbolicBayesTree.h index 4d5804b27b..275b9560d4 100644 --- a/gtsam/symbolic/SymbolicBayesTree.h +++ b/gtsam/symbolic/SymbolicBayesTree.h @@ -39,7 +39,6 @@ namespace gtsam { typedef std::shared_ptr shared_ptr; typedef std::weak_ptr weak_ptr; SymbolicBayesTreeClique() {} - virtual ~SymbolicBayesTreeClique() {} SymbolicBayesTreeClique(const std::shared_ptr& conditional) : Base(conditional) {} }; diff --git a/gtsam/symbolic/SymbolicFactor.h b/gtsam/symbolic/SymbolicFactor.h index 0e9eb3d467..b4b9b6dab4 100644 --- a/gtsam/symbolic/SymbolicFactor.h +++ b/gtsam/symbolic/SymbolicFactor.h @@ -79,7 +79,7 @@ namespace gtsam { /** Create symbolic version of any factor */ explicit SymbolicFactor(const Factor& factor) : Base(factor.keys()) {} - virtual ~SymbolicFactor() {} + virtual ~SymbolicFactor() override {} /// Copy this object as its actual derived type. SymbolicFactor::shared_ptr clone() const { return std::make_shared(*this); } diff --git a/gtsam/symbolic/SymbolicFactorGraph.h b/gtsam/symbolic/SymbolicFactorGraph.h index fdd5bc27c5..4122031d05 100644 --- a/gtsam/symbolic/SymbolicFactorGraph.h +++ b/gtsam/symbolic/SymbolicFactorGraph.h @@ -111,9 +111,6 @@ namespace gtsam { return *this; } - /// Destructor - virtual ~SymbolicFactorGraph() {} - /// @} /// @name Testable diff --git a/gtsam_unstable/slam/SmartProjectionPoseFactorRollingShutter.h b/gtsam_unstable/slam/SmartProjectionPoseFactorRollingShutter.h index e2e71cc03a..4af0be7517 100644 --- a/gtsam_unstable/slam/SmartProjectionPoseFactorRollingShutter.h +++ b/gtsam_unstable/slam/SmartProjectionPoseFactorRollingShutter.h @@ -113,9 +113,6 @@ class GTSAM_UNSTABLE_EXPORT SmartProjectionPoseFactorRollingShutter "linearizationMode must be set to HESSIAN"); } - /** Virtual destructor */ - ~SmartProjectionPoseFactorRollingShutter() override = default; - /** * add a new measurement, with 2 pose keys, interpolation factor, and cameraId * @param measured 2-dimensional location of the projection of a single diff --git a/gtsam_unstable/slam/SmartStereoProjectionFactorPP.h b/gtsam_unstable/slam/SmartStereoProjectionFactorPP.h index 529a1dc106..f9db909533 100644 --- a/gtsam_unstable/slam/SmartStereoProjectionFactorPP.h +++ b/gtsam_unstable/slam/SmartStereoProjectionFactorPP.h @@ -79,9 +79,6 @@ class GTSAM_UNSTABLE_EXPORT SmartStereoProjectionFactorPP const SmartStereoProjectionParams& params = SmartStereoProjectionParams()); - /** Virtual destructor */ - ~SmartStereoProjectionFactorPP() override = default; - /** * add a new measurement, with a pose key, and an extrinsic pose key * @param measured is the 3-dimensional location of the projection of a diff --git a/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h b/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h index cce265ab7d..77a15c246c 100644 --- a/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h +++ b/gtsam_unstable/slam/SmartStereoProjectionPoseFactor.h @@ -71,9 +71,6 @@ class GTSAM_UNSTABLE_EXPORT SmartStereoProjectionPoseFactor const SmartStereoProjectionParams& params = SmartStereoProjectionParams(), const std::optional& body_P_sensor = {}); - /** Virtual destructor */ - ~SmartStereoProjectionPoseFactor() override = default; - /** * add a new measurement and pose key * @param measured is the 2m dimensional location of the projection of a