Skip to content

Commit

Permalink
Fixed warnings that arise from stricter compiler flags
Browse files Browse the repository at this point in the history
  • Loading branch information
dellaert committed Feb 11, 2023
1 parent b71ed8f commit a8eb98a
Show file tree
Hide file tree
Showing 64 changed files with 126 additions and 181 deletions.
3 changes: 1 addition & 2 deletions CppUnitLite/Test.h
Original file line number Diff line number Diff line change
Expand Up @@ -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;

Expand Down Expand Up @@ -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_)
Expand Down
2 changes: 1 addition & 1 deletion CppUnitLite/TestResult.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ class TestResult
{
public:
TestResult ();
virtual ~TestResult() {};
virtual ~TestResult() {}
virtual void testsStarted ();
virtual void addFailure (const Failure& failure);
virtual void testsEnded ();
Expand Down
2 changes: 2 additions & 0 deletions cmake/GtsamBuildTypes.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -130,6 +130,8 @@ else()
$<$<CXX_COMPILER_ID:GNU>:-Wreturn-local-addr -Werror=return-local-addr> # Error: return local address
$<$<CXX_COMPILER_ID:Clang>:-Wreturn-stack-address -Werror=return-stack-address> # Error: return local address
$<$<CXX_COMPILER_ID:Clang>:-Wno-misleading-indentation> # Eigen triggers a ton!
$<$<CXX_COMPILER_ID:Clang>:-Wno-weak-template-vtables> # TODO(dellaert): don't know how to resolve
$<$<CXX_COMPILER_ID:Clang>:-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
$<$<COMPILE_LANGUAGE:CXX>:${flag_override_}> # Enforce the use of the override keyword
Expand Down
4 changes: 2 additions & 2 deletions gtsam/base/DSFMap.h
Original file line number Diff line number Diff line change
Expand Up @@ -118,8 +118,8 @@ class IndexPair : public std::pair<size_t,size_t> {
public:
inline IndexPair(): std::pair<size_t,size_t>(0,0) {}
inline IndexPair(size_t i, size_t j) : std::pair<size_t,size_t>(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<IndexPair> IndexPairVector;
Expand Down
10 changes: 5 additions & 5 deletions gtsam/base/concepts.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion gtsam/base/types.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);

Expand Down
3 changes: 0 additions & 3 deletions gtsam/discrete/DiscreteBayesNet.h
Original file line number Diff line number Diff line change
Expand Up @@ -65,9 +65,6 @@ class GTSAM_EXPORT DiscreteBayesNet: public BayesNet<DiscreteConditional> {
DiscreteBayesNet(const FactorGraph<DERIVEDCONDITIONAL>& graph)
: Base(graph) {}

/// Destructor
virtual ~DiscreteBayesNet() {}

/// @}

/// @name Testable
Expand Down
1 change: 0 additions & 1 deletion gtsam/discrete/DiscreteBayesTree.h
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,6 @@ class GTSAM_EXPORT DiscreteBayesTreeClique
typedef std::shared_ptr<This> shared_ptr;
typedef std::weak_ptr<This> weak_ptr;
DiscreteBayesTreeClique() {}
virtual ~DiscreteBayesTreeClique() {}
DiscreteBayesTreeClique(
const std::shared_ptr<DiscreteConditional>& conditional)
: Base(conditional) {}
Expand Down
4 changes: 0 additions & 4 deletions gtsam/discrete/DiscreteFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -59,10 +59,6 @@ class GTSAM_EXPORT DiscreteFactor: public Factor {
template<typename CONTAINER>
DiscreteFactor(const CONTAINER& keys) : Base(keys) {}

/// Virtual destructor
virtual ~DiscreteFactor() {
}

/// @}
/// @name Testable
/// @{
Expand Down
3 changes: 0 additions & 3 deletions gtsam/discrete/DiscreteFactorGraph.h
Original file line number Diff line number Diff line change
Expand Up @@ -111,9 +111,6 @@ class GTSAM_EXPORT DiscreteFactorGraph
template <class DERIVEDFACTOR>
DiscreteFactorGraph(const FactorGraph<DERIVEDFACTOR>& graph) : Base(graph) {}

/// Destructor
virtual ~DiscreteFactorGraph() {}

/// @name Testable
/// @{

Expand Down
3 changes: 0 additions & 3 deletions gtsam/discrete/DiscreteLookupDAG.h
Original file line number Diff line number Diff line change
Expand Up @@ -89,9 +89,6 @@ class GTSAM_EXPORT DiscreteLookupDAG : public BayesNet<DiscreteLookupTable> {
/// Create from BayesNet with LookupTables
static DiscreteLookupDAG FromBayesNet(const DiscreteBayesNet& bayesNet);

/// Destructor
virtual ~DiscreteLookupDAG() {}

/// @}

/// @name Testable
Expand Down
4 changes: 2 additions & 2 deletions gtsam/discrete/SignatureParser.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ std::optional<Row> static ParseConditional(const std::string& token) {
} catch (...) {
return std::nullopt;
}
return row;
return std::move(row);
}

std::optional<Table> static ParseConditionalTable(
Expand All @@ -62,7 +62,7 @@ std::optional<Table> static ParseConditionalTable(
}
}
}
return table;
return std::move(table);
}

std::vector<std::string> static Tokenize(const std::string& str) {
Expand Down
3 changes: 2 additions & 1 deletion gtsam/geometry/Cal3Bundler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
2 changes: 1 addition & 1 deletion gtsam/geometry/Cal3DS2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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 {
Expand Down
6 changes: 3 additions & 3 deletions gtsam/geometry/Cal3DS2_Base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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");
}

/* ************************************************************************* */
Expand Down
6 changes: 3 additions & 3 deletions gtsam/geometry/Cal3Fisheye.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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");
}

/* ************************************************************************* */
Expand Down
8 changes: 0 additions & 8 deletions gtsam/geometry/CalibratedCamera.h
Original file line number Diff line number Diff line change
Expand Up @@ -308,14 +308,6 @@ class GTSAM_EXPORT CalibratedCamera: public PinholeBase {
PinholeBase(v) {
}

/// @}
/// @name Standard Interface
/// @{

/// destructor
virtual ~CalibratedCamera() {
}

/// @}
/// @name Manifold
/// @{
Expand Down
2 changes: 1 addition & 1 deletion gtsam/geometry/PinholeCamera.h
Original file line number Diff line number Diff line change
Expand Up @@ -321,7 +321,7 @@ class PinholeCamera: public PinholeBaseK<Calibration> {

/// for Nonlinear Triangulation
Vector defaultErrorWhenTriangulatingBehindCamera() const {
return Eigen::Matrix<double,traits<Point2>::dimension,1>::Constant(2.0 * K_.fx());;
return Eigen::Matrix<double,traits<Point2>::dimension,1>::Constant(2.0 * K_.fx());
}

private:
Expand Down
4 changes: 2 additions & 2 deletions gtsam/geometry/PinholePose.h
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ class PinholeBaseK: public PinholeBase {
/// @name Standard Interface
/// @{

virtual ~PinholeBaseK() {
virtual ~PinholeBaseK() override {
}

/// return calibration
Expand Down Expand Up @@ -425,7 +425,7 @@ class PinholePose: public PinholeBaseK<CALIBRATION> {

/// for Nonlinear Triangulation
Vector defaultErrorWhenTriangulatingBehindCamera() const {
return Eigen::Matrix<double,traits<Point2>::dimension,1>::Constant(2.0 * K_->fx());;
return Eigen::Matrix<double,traits<Point2>::dimension,1>::Constant(2.0 * K_->fx());
}
/// @}

Expand Down
2 changes: 1 addition & 1 deletion gtsam/geometry/StereoCamera.h
Original file line number Diff line number Diff line change
Expand Up @@ -172,7 +172,7 @@ class GTSAM_EXPORT StereoCamera {

/// for Nonlinear Triangulation
Vector defaultErrorWhenTriangulatingBehindCamera() const {
return Eigen::Matrix<double,traits<Measurement>::dimension,1>::Constant(2.0 * K_->fx());;
return Eigen::Matrix<double,traits<Measurement>::dimension,1>::Constant(2.0 * K_->fx());
}

/// @}
Expand Down
2 changes: 0 additions & 2 deletions gtsam/hybrid/HybridBayesTree.h
Original file line number Diff line number Diff line change
Expand Up @@ -55,8 +55,6 @@ class GTSAM_EXPORT HybridBayesTreeClique
: Base(conditional) {}
///< Copy constructor
HybridBayesTreeClique(const HybridBayesTreeClique& clique) : Base(clique) {}

virtual ~HybridBayesTreeClique() {}
};

/* ************************************************************************* */
Expand Down
3 changes: 0 additions & 3 deletions gtsam/hybrid/HybridFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -97,9 +97,6 @@ class GTSAM_EXPORT HybridFactor : public Factor {
HybridFactor(const KeyVector &continuousKeys,
const DiscreteKeys &discreteKeys);

/// Virtual destructor
virtual ~HybridFactor() = default;

/// @}
/// @name Testable
/// @{
Expand Down
2 changes: 1 addition & 1 deletion gtsam/hybrid/HybridGaussianFactorGraph.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -287,7 +287,7 @@ hybridElimination(const HybridGaussianFactorGraph &factors,
auto hf = std::dynamic_pointer_cast<HessianFactor>(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,
Expand Down
24 changes: 12 additions & 12 deletions gtsam/hybrid/HybridValues.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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 {
Expand All @@ -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.
Expand All @@ -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) {
Expand Down Expand Up @@ -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
Expand Down Expand Up @@ -227,7 +227,7 @@ class GTSAM_EXPORT HybridValues {
ss << this->continuous_.html(keyFormatter);
ss << this->discrete_.html(keyFormatter);
return ss.str();
};
}

/// @}
};
Expand Down
2 changes: 0 additions & 2 deletions gtsam/hybrid/MixtureFactor.h
Original file line number Diff line number Diff line change
Expand Up @@ -123,8 +123,6 @@ class MixtureFactor : public HybridFactor {
}
}

~MixtureFactor() = default;

/**
* @brief Compute error of the MixtureFactor as a tree.
*
Expand Down
1 change: 1 addition & 0 deletions gtsam/inference/LabeledSymbol.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
#include <gtsam/inference/LabeledSymbol.h>

#include <iostream>
#include <limits>

namespace gtsam {

Expand Down
2 changes: 1 addition & 1 deletion gtsam/inference/Symbol.h
Original file line number Diff line number Diff line change
Expand Up @@ -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 {
Expand Down
1 change: 1 addition & 0 deletions gtsam/inference/VariableSlots.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
#include <gtsam/inference/VariableSlots.h>

#include <iostream>
#include <limits>

using namespace std;

Expand Down
3 changes: 0 additions & 3 deletions gtsam/linear/GaussianBayesNet.h
Original file line number Diff line number Diff line change
Expand Up @@ -74,9 +74,6 @@ namespace gtsam {
std::initializer_list<std::shared_ptr<DERIVEDCONDITIONAL> > conditionals)
: Base(conditionals) {}

/// Destructor
virtual ~GaussianBayesNet() = default;

/// @}

/// @name Testable
Expand Down
1 change: 0 additions & 1 deletion gtsam/linear/GaussianBayesTree.h
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,6 @@ namespace gtsam {
typedef std::shared_ptr<This> shared_ptr;
typedef std::weak_ptr<This> weak_ptr;
GaussianBayesTreeClique() {}
virtual ~GaussianBayesTreeClique() {}
GaussianBayesTreeClique(const std::shared_ptr<GaussianConditional>& conditional) : Base(conditional) {}
};

Expand Down
Loading

0 comments on commit a8eb98a

Please sign in to comment.