Skip to content

Commit

Permalink
Merge pull request #1959 from mcm001/wall-wpedantic
Browse files Browse the repository at this point in the history
Enable more warnings and remove unused variables
  • Loading branch information
dellaert authored Jan 10, 2025
2 parents 169523e + fd2f39e commit 89fbe4b
Show file tree
Hide file tree
Showing 13 changed files with 25 additions and 17 deletions.
4 changes: 2 additions & 2 deletions .github/workflows/build-linux.yml
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ jobs:
name: [
ubuntu-20.04-gcc-9,
ubuntu-20.04-clang-9,
ubuntu-22.04-gcc-11,
ubuntu-22.04-gcc-12,
ubuntu-22.04-clang-14,
]

Expand All @@ -44,7 +44,7 @@ jobs:
compiler: clang
version: "9"

- name: ubuntu-22.04-gcc-11
- name: ubuntu-22.04-gcc-12
os: ubuntu-22.04
compiler: gcc
version: "11"
Expand Down
13 changes: 8 additions & 5 deletions cmake/GtsamBuildTypes.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -111,7 +111,7 @@ if(MSVC)
set(CMAKE_3_15 $<VERSION_LESS:${CMAKE_VERSION},3.15>)
set(CMAKE_3_25 $<VERSION_LESS:${CMAKE_VERSION},3.25>)
# Common to all configurations, next for each configuration:
set(GTSAM_COMPILE_OPTIONS_PRIVATE_COMMON /W3 /GR /EHsc /MP CACHE STRING "(User editable) Private compiler flags for all configurations.")
set(GTSAM_COMPILE_OPTIONS_PRIVATE_COMMON /W3 /WX /GR /EHsc /MP CACHE STRING "(User editable) Private compiler flags for all configurations.")
set(GTSAM_COMPILE_OPTIONS_PRIVATE_DEBUG $<${CMAKE_3_15}:/MDd> $<${CMAKE_3_25}:/Zi> /Ob0 /Od /RTC1 CACHE STRING "(User editable) Private compiler flags for Debug configuration.")
set(GTSAM_COMPILE_OPTIONS_PRIVATE_RELWITHDEBINFO $<${CMAKE_3_15}:/MD> /O2 $<${CMAKE_3_25}:/Zi> CACHE STRING "(User editable) Private compiler flags for RelWithDebInfo configuration.")
set(GTSAM_COMPILE_OPTIONS_PRIVATE_RELEASE $<${CMAKE_3_15}:/MD> /O2 CACHE STRING "(User editable) Private compiler flags for Release configuration.")
Expand All @@ -131,12 +131,15 @@ else()
endif()

set(GTSAM_COMPILE_OPTIONS_PRIVATE_COMMON
-Werror # Enable warnings as errors
-Wall # Enable common warnings
$<$<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-weak-template-vtables> # TODO(dellaert): don't know how to resolve
-Wpedantic # Enable pedantic warnings
$<$<COMPILE_LANGUAGE:CXX>:-Wextra -Wno-unused-parameter> # Enable extra warnings, but ignore no-unused-parameter (as we ifdef out chunks of code)
$<$<CXX_COMPILER_ID:GNU>:-Wreturn-local-addr> # Error: return local address
$<$<CXX_COMPILER_ID:Clang>:-Wreturn-stack-address> # Error: return local address
$<$<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()
-Wreturn-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
3 changes: 2 additions & 1 deletion gtsam/base/TestableAssertions.h
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,8 @@ namespace gtsam {
/**
* Equals testing for basic types
*/
inline bool assert_equal(const Key& expected, const Key& actual, double tol = 0.0) {
inline bool assert_equal(const Key& expected, const Key& actual) {
// TODO - why isn't tol used?
if(expected != actual) {
std::cout << "Not equal:\nexpected: " << expected << "\nactual: " << actual << std::endl;
return false;
Expand Down
1 change: 0 additions & 1 deletion gtsam/geometry/Line3.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,6 @@ Line3 transformTo(const Pose3 &wTc, const Line3 &wL,
Rot3 cRw = wRc.inverse();
Rot3 cRl = cRw * wL.R_;

Vector2 w_ab;
Vector3 t = ((wL.R_).transpose() * wTc.translation());
Vector2 c_ab(wL.a_ - t[0], wL.b_ - t[1]);

Expand Down
5 changes: 2 additions & 3 deletions gtsam/geometry/Pose3.h
Original file line number Diff line number Diff line change
Expand Up @@ -56,9 +56,8 @@ class GTSAM_EXPORT Pose3: public LieGroup<Pose3, 6> {

/** Copy constructor */
Pose3(const Pose3& pose) = default;
// :
// R_(pose.R_), t_(pose.t_) {
// }

Pose3& operator=(const Pose3& other) = default;

/** Construct from R,t */
Pose3(const Rot3& R, const Point3& t) :
Expand Down
3 changes: 2 additions & 1 deletion gtsam/geometry/Rot2.h
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,8 @@ namespace gtsam {

/** copy constructor */
Rot2(const Rot2& r) = default;
// : Rot2(r.c_, r.s_) {}

Rot2& operator=(const Rot2& other) = default;

/// Constructor from angle in radians == exponential map at identity
Rot2(double theta) : c_(cos(theta)), s_(sin(theta)) {}
Expand Down
1 change: 0 additions & 1 deletion gtsam/geometry/SO4.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -107,7 +107,6 @@ SO4 SO4::Expmap(const Vector6& xi, ChartJacobian H) {
}

// Build expX = exp(xi^)
Matrix4 expX;
using std::cos;
using std::sin;
const auto X2 = X * X;
Expand Down
1 change: 0 additions & 1 deletion gtsam/geometry/Similarity3.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,6 @@ static Point3Pairs subtractCentroids(const Point3Pairs &abPointPairs,
static double calculateScale(const Point3Pairs &d_abPointPairs,
const Rot3 &aRb) {
double x = 0, y = 0;
Point3 da, db;
for (const auto& [da, db] : d_abPointPairs) {
const Vector3 da_prime = aRb * db;
y += da.transpose() * da_prime;
Expand Down
2 changes: 1 addition & 1 deletion gtsam/hybrid/HybridGaussianProductFactor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ static Y add(const Y& y1, const Y& y2) {
GaussianFactorGraph result = y1.first;
result.push_back(y2.first);
return {result, y1.second + y2.second};
};
}

/* *******************************************************************************/
HybridGaussianProductFactor operator+(const HybridGaussianProductFactor& a,
Expand Down
3 changes: 2 additions & 1 deletion gtsam/linear/VectorValues.h
Original file line number Diff line number Diff line change
Expand Up @@ -106,7 +106,7 @@ namespace gtsam {
template<class CONTAINER>
explicit VectorValues(const CONTAINER& c) : values_(c.begin(), c.end()) {}

/** Implicit copy constructor to specialize the explicit constructor from any container. */
/** Copy constructor to specialize the explicit constructor from any container. */
VectorValues(const VectorValues& c) : values_(c.values_) {}

/** Create from a pair of iterators over pair<Key,Vector>. */
Expand All @@ -119,6 +119,7 @@ namespace gtsam {
/// Constructor from Vector, with Scatter
VectorValues(const Vector& c, const Scatter& scatter);

// We override the copy constructor; expicitly declare operator=
VectorValues& operator=(const VectorValues& other) = default;

/** Create a VectorValues with the same structure as \c other, but filled with zeros. */
Expand Down
2 changes: 2 additions & 0 deletions gtsam_unstable/base/Dummy.h
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,8 @@ namespace gtsam {
size_t id;
Dummy();
~Dummy();
Dummy(const Dummy& other) = default;
Dummy& operator=(const Dummy& other) = default;
void print(const std::string& s="") const ;
unsigned char dummyTwoVar(unsigned char a) const ;
};
Expand Down
2 changes: 2 additions & 0 deletions gtsam_unstable/base/FixedVector.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,8 @@ class FixedVector : public Eigen::Matrix<double, N, 1> {
/** copy constructors */
FixedVector(const FixedVector& v) : Base(v) {}

FixedVector& operator=(const FixedVector& other) = default;

/** Convert from a variable-size vector to a fixed size vector */
FixedVector(const Vector& v) : Base(v) {}

Expand Down
2 changes: 2 additions & 0 deletions gtsam_unstable/slam/Mechanization_bRn2.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,8 @@ class GTSAM_UNSTABLE_EXPORT Mechanization_bRn2 {
/// Copy constructor
Mechanization_bRn2(const Mechanization_bRn2& other) = default;

Mechanization_bRn2& operator=(const Mechanization_bRn2& other) = default;

/// gravity in the body frame
Vector3 b_g(double g_e) const {
Vector3 n_g(0, 0, g_e);
Expand Down

0 comments on commit 89fbe4b

Please sign in to comment.