Skip to content

Commit

Permalink
Please clang-tidy on Ubuntu Noble
Browse files Browse the repository at this point in the history
Signed-off-by: Michel Hidalgo <michel@ekumenlabs.com>
  • Loading branch information
hidmic committed May 21, 2024
1 parent 530d8b1 commit 4b3cd5f
Show file tree
Hide file tree
Showing 84 changed files with 734 additions and 378 deletions.
1 change: 1 addition & 0 deletions .clang-format
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@ Language: Cpp
PointerAlignment: Left
ColumnLimit: 120
AlignAfterOpenBracket: AlwaysBreak
QualifierAlignment: Left
---
BasedOnStyle: Chromium
Language: JavaScript
Expand Down
1 change: 1 addition & 0 deletions .clang-tidy
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@ Checks: >
readability-*,
-google-readability-braces-around-statements,
-google-runtime-references,
-misc-include-cleaner,
-misc-non-private-member-variables-in-classes,
-modernize-return-braced-init-list,
-modernize-use-trailing-return-type,
Expand Down
1 change: 0 additions & 1 deletion .github/workflows/ci_pipeline.yml
Original file line number Diff line number Diff line change
Expand Up @@ -93,7 +93,6 @@ jobs:
- name: Perform static analysis
working-directory: ${{ github.workspace }}
run: ./src/beluga/tools/run-clang-tidy.sh
if: ${{ matrix.ros_distro != "jazzy" }}

- name: Upload code coverage report
uses: codecov/codecov-action@v3
Expand Down
6 changes: 3 additions & 3 deletions beluga/include/beluga/actions/normalize.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,13 +18,13 @@
#include <algorithm>
#include <execution>

#include <beluga/type_traits/particle_traits.hpp>
#include <beluga/views/particles.hpp>

#include <range/v3/action/action.hpp>
#include <range/v3/numeric/accumulate.hpp>
#include <range/v3/view/common.hpp>

#include <beluga/type_traits/particle_traits.hpp>
#include <beluga/views/particles.hpp>

/**
* \file
* \brief Implementation of the normalize range adaptor object.
Expand Down
2 changes: 1 addition & 1 deletion beluga/include/beluga/algorithm/distance_map.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ auto nearest_obstacle_distance_map(
while (!queue.empty()) {
auto parent = queue.top();
queue.pop();
for (std::size_t index : neighbors_function(parent.index)) {
for (const std::size_t index : neighbors_function(parent.index)) {
if (!visited[index]) {
visited[index] = true;
distance_map[index] = distance_function(parent.nearest_obstacle_index, index);
Expand Down
3 changes: 2 additions & 1 deletion beluga/include/beluga/algorithm/raycasting/bresenham.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#ifndef BELUGA_ALGORITHM_RAYCASTING_BRESENHAM_HPP
#define BELUGA_ALGORITHM_RAYCASTING_BRESENHAM_HPP

#include <cstdint>
#include <utility>

#include <range/v3/view/all.hpp>
Expand All @@ -33,7 +34,7 @@ namespace beluga {
class Bresenham2i {
public:
/// Bresenham's 2D line drawing algorithm variants.
enum Variant {
enum Variant : std::uint8_t {
kStandard = 0, ///< Standard Bresenham's algorithm.
kModified ///< Modified, aka supercover, Bresenham's algorithm.
/// See http://eugen.dedu.free.fr/projects/bresenham.
Expand Down
20 changes: 10 additions & 10 deletions beluga/include/beluga/containers/circular_array.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@
namespace beluga {

/// Feature flags for circular arrays.
enum class CircularArrayFeatureFlags : int {
enum class CircularArrayFeatureFlags : std::int8_t {
kNone = 0x00,
kRolloverOnWrite = 0x01, ///<! If enabled, older values in the array are overwritten by
/// newer values if the array has reached its maximum size already.
Expand All @@ -43,17 +43,17 @@ enum class CircularArrayFeatureFlags : int {
};

/// Bitwise OR operator overload to combine two feature flags in a single mask-like flag.
inline constexpr CircularArrayFeatureFlags operator|(CircularArrayFeatureFlags lflag, CircularArrayFeatureFlags rflag) {
return static_cast<CircularArrayFeatureFlags>(
static_cast<typename std::underlying_type<CircularArrayFeatureFlags>::type>(lflag) |
static_cast<typename std::underlying_type<CircularArrayFeatureFlags>::type>(rflag));
constexpr CircularArrayFeatureFlags operator|(CircularArrayFeatureFlags lflag, CircularArrayFeatureFlags rflag) {
return static_cast<CircularArrayFeatureFlags>( // NOLINT(lang-analyzer-optin.core.EnumCastOutOfRange)
static_cast<std::underlying_type_t<CircularArrayFeatureFlags>>(lflag) |
static_cast<std::underlying_type_t<CircularArrayFeatureFlags>>(rflag));
}

/// Bitwise AND operator overload to check of the presence of a feature `flag` in a feature `mask`.
inline constexpr bool operator&(CircularArrayFeatureFlags mask, CircularArrayFeatureFlags flag) {
constexpr bool operator&(CircularArrayFeatureFlags mask, CircularArrayFeatureFlags flag) {
return static_cast<bool>(
static_cast<typename std::underlying_type<CircularArrayFeatureFlags>::type>(mask) &
static_cast<typename std::underlying_type<CircularArrayFeatureFlags>::type>(flag));
static_cast<std::underlying_type_t<CircularArrayFeatureFlags>>(mask) &
static_cast<std::underlying_type_t<CircularArrayFeatureFlags>>(flag));
}

/// An implementation of generic, non-threadsafe circular array.
Expand Down Expand Up @@ -228,7 +228,7 @@ class CircularArray {
* \throws std::length_error If the array is full and
* the rollover on write feature is not enabled.
*/
template <bool Enabled = F& CircularArrayFeatureFlags::kLayoutReversal>
template <bool Enabled = (F & CircularArrayFeatureFlags::kLayoutReversal)>
std::enable_if_t<Enabled> push_front(value_type value) {
static_assert(
F & CircularArrayFeatureFlags::kLayoutReversal,
Expand All @@ -250,7 +250,7 @@ class CircularArray {
* Behavior is undefined when popping from the back of an empty array.
* No destructors are invoked on the value popped.
*/
template <bool Enabled = F& CircularArrayFeatureFlags::kLayoutReversal>
template <bool Enabled = (F & CircularArrayFeatureFlags::kLayoutReversal)>
std::enable_if_t<Enabled> pop_back() noexcept {
--size_;
}
Expand Down
4 changes: 2 additions & 2 deletions beluga/include/beluga/sensor/bearing_sensor_model.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,8 +40,8 @@ namespace beluga {

/// Parameters used to construct a BearingSensorModel instance.
struct BearingModelParam {
double sigma_bearing{1.0}; ///< Standard deviation of the bearing error.
Sophus::SE3d sensor_pose_in_robot{}; ///< Pose of the sensor in the robot reference frame.
double sigma_bearing{1.0}; ///< Standard deviation of the bearing error.
Sophus::SE3d sensor_pose_in_robot; ///< Pose of the sensor in the robot reference frame.
};

/// Generic bearing sensor model, for both 2D and 3D state types.
Expand Down
12 changes: 6 additions & 6 deletions beluga/include/beluga/sensor/data/ndt_cell.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,17 +18,17 @@
#include <ostream>
#include <type_traits>

#include <beluga/sensor/data/sparse_value_grid.hpp>

#include <Eigen/Core>

#include <Eigen/src/Core/util/Constants.h>
#include <range/v3/view/zip.hpp>

#include <sophus/common.hpp>
#include <sophus/se2.hpp>
#include <sophus/se3.hpp>
#include <sophus/so2.hpp>

#include "beluga/sensor/data/sparse_value_grid.hpp"

namespace beluga {

/// Representation for a cell of a N dimensional NDT cell.
Expand All @@ -54,21 +54,21 @@ struct NDTCell {
}

/// Ostream overload mostly for debugging purposes.
friend inline std::ostream& operator<<(std::ostream& os, const NDTCell& cell) {
friend std::ostream& operator<<(std::ostream& os, const NDTCell& cell) {
os << "Mean \n" << cell.mean.transpose() << " \n\nCovariance: \n" << cell.covariance;
return os;
}

/// Transform the normal distribution according to tf, both mean and covariance.
friend inline NDTCell operator*(const Sophus::SE2<scalar_type>& tf, const NDTCell& ndt_cell) {
friend NDTCell operator*(const Sophus::SE2<scalar_type>& tf, const NDTCell& ndt_cell) {
static_assert(num_dim == 2, "Cannot transform a non 2D NDT Cell with a SE2 transform.");
const Eigen::Vector2d uij = tf * ndt_cell.mean;
const Eigen::Matrix2Xd cov = tf.so2().matrix() * ndt_cell.covariance * tf.so2().matrix().transpose();
return NDTCell{uij, cov};
}

/// Transform the normal distribution according to tf, both mean and covariance.
friend inline NDTCell operator*(const Sophus::SE3<scalar_type>& tf, const NDTCell& ndt_cell) {
friend NDTCell operator*(const Sophus::SE3<scalar_type>& tf, const NDTCell& ndt_cell) {
static_assert(num_dim == 3, "Cannot transform a non 3D NDT Cell with a SE3 transform.");
const Eigen::Vector3d uij = tf * ndt_cell.mean;
const Eigen::Matrix3Xd cov = tf.so2().matrix() * ndt_cell.covariance * tf.so2().matrix().transpose();
Expand Down
2 changes: 1 addition & 1 deletion beluga/include/beluga/sensor/data/occupancy_grid.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,7 @@ template <typename Derived>
class BaseOccupancyGrid2 : public BaseLinearGrid2<Derived> {
public:
/// Coordinate frames.
enum class Frame { kLocal, kGlobal };
enum class Frame : std::uint8_t { kLocal, kGlobal };

/// Checks if cell is free.
/**
Expand Down
36 changes: 18 additions & 18 deletions beluga/include/beluga/sensor/ndt_sensor_model.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,26 +15,26 @@
#ifndef BELUGA_SENSOR_NDT_SENSOR_MODEL_HPP
#define BELUGA_SENSOR_NDT_SENSOR_MODEL_HPP

#include <beluga/sensor/data/ndt_cell.hpp>
#include <beluga/sensor/data/sparse_value_grid.hpp>

#include <Eigen/src/Core/Matrix.h>
#include <H5Cpp.h>
#include <cassert>
#include <sophus/common.hpp>
#include <sophus/se2.hpp>
#include <sophus/se3.hpp>
#include <sophus/so2.hpp>

#include <Eigen/Core>

#include <cstdint>
#include <filesystem>
#include <stdexcept>
#include <type_traits>
#include <unordered_map>
#include <vector>

#include <H5Cpp.h>

#include <Eigen/Core>

#include <sophus/common.hpp>
#include <sophus/se2.hpp>
#include <sophus/se3.hpp>
#include <sophus/so2.hpp>

#include <beluga/sensor/data/ndt_cell.hpp>
#include <beluga/sensor/data/sparse_value_grid.hpp>

namespace beluga {

namespace detail {
Expand Down Expand Up @@ -82,7 +82,7 @@ inline std::vector<NDTCell<NDim, Scalar>> to_cells(
const double resolution) {
static constexpr int kMinPointsPerCell = 5;

Eigen::Map<const Eigen::Matrix<Scalar, NDim, Eigen::Dynamic>> points_view(
const Eigen::Map<const Eigen::Matrix<Scalar, NDim, Eigen::Dynamic>> points_view(
reinterpret_cast<const Scalar*>(points.data()), NDim, static_cast<int64_t>(points.size()));

std::vector<NDTCell<NDim, Scalar>> ret;
Expand Down Expand Up @@ -247,11 +247,11 @@ NDTMapRepresentationT load_from_hdf5_2d(const std::filesystem::path& path_to_hdf
throw std::invalid_argument(ss.str());
}

H5::H5File file(path_to_hdf5_file, H5F_ACC_RDONLY);
H5::DataSet means_dataset = file.openDataSet("means");
H5::DataSet covariances_dataset = file.openDataSet("covariances");
H5::DataSet resolution_dataset = file.openDataSet("resolution");
H5::DataSet cells_dataset = file.openDataSet("cells");
const H5::H5File file(path_to_hdf5_file, H5F_ACC_RDONLY);
const H5::DataSet means_dataset = file.openDataSet("means");
const H5::DataSet covariances_dataset = file.openDataSet("covariances");
const H5::DataSet resolution_dataset = file.openDataSet("resolution");
const H5::DataSet cells_dataset = file.openDataSet("cells");

std::array<hsize_t, 2> dims_out;
means_dataset.getSpace().getSimpleExtentDims(dims_out.data(), nullptr);
Expand Down
2 changes: 1 addition & 1 deletion beluga/include/beluga/type_traits/tuple_traits.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -105,7 +105,7 @@ static constexpr std::size_t kTupleIndexAmbiguous = static_cast<std::size_t>(-2)
template <class T, class... Args>
constexpr std::size_t tuple_index_helper() noexcept {
constexpr bool kMatches[sizeof...(Args)] = // NOLINT(modernize-avoid-c-arrays)
{std::is_same<T, std::decay_t<Args>>::value...};
{std::is_same_v<T, std::decay_t<Args>>...};
std::size_t selected = kTupleIndexNotFound;
for (std::size_t i = 0; i < sizeof...(Args); ++i) {
if (kMatches[i]) {
Expand Down
2 changes: 1 addition & 1 deletion beluga/include/beluga/utility/forward_like.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ template <class T, class U>
if constexpr (is_adding_const) {
return std::as_const(value);
} else {
return static_cast<U&>(value);
return value;
}
} else {
if constexpr (is_adding_const) {
Expand Down
10 changes: 5 additions & 5 deletions beluga/include/beluga/views/take_while_kld.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,11 +18,11 @@
#include <cmath>
#include <unordered_set>

#include <beluga/type_traits/particle_traits.hpp>

#include <range/v3/view/take.hpp>
#include <range/v3/view/take_while.hpp>

#include <beluga/type_traits/particle_traits.hpp>

/**
* \file
* \brief Implementation of a take_while_kld range adaptor object.
Expand Down Expand Up @@ -74,9 +74,9 @@ inline auto kld_condition(std::size_t min, double epsilon, double z = beluga::de
if (k <= 2U) {
return std::numeric_limits<std::size_t>::max();
}
double common = 2. / static_cast<double>(9 * (k - 1));
double base = 1. - common + std::sqrt(common) * z;
double result = (static_cast<double>(k - 1) / two_epsilon) * base * base * base;
const double common = 2. / static_cast<double>(9 * (k - 1));
const double base = 1. - common + std::sqrt(common) * z;
const double result = (static_cast<double>(k - 1) / two_epsilon) * base * base * base;
return static_cast<std::size_t>(std::ceil(result));
};

Expand Down
4 changes: 2 additions & 2 deletions beluga/include/ciabatta/ciabatta.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,8 +34,8 @@ struct ciabatta_top { /* not a mixin */
using self_type = MostDerived;
[[nodiscard]] decltype(auto) self() & { return static_cast<self_type&>(*this); }
[[nodiscard]] decltype(auto) self() && { return static_cast<self_type&&>(*this); }
[[nodiscard]] decltype(auto) self() const& { return static_cast<self_type const&>(*this); }
[[nodiscard]] decltype(auto) self() const&& { return static_cast<self_type const&&>(*this); }
[[nodiscard]] decltype(auto) self() const& { return static_cast<const self_type&>(*this); }
[[nodiscard]] decltype(auto) self() const&& { return static_cast<const self_type&&>(*this); }
};

struct deferred {
Expand Down
7 changes: 7 additions & 0 deletions beluga/test/.clang-tidy
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
---
# Configure clang-tidy for this project tests.

InheritParentConfig: true

Checks: >
-bugprone-unchecked-optional-access
11 changes: 7 additions & 4 deletions beluga/test/beluga/actions/test_normalize.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,12 +12,15 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include <gmock/gmock.h>
#include <gtest/gtest.h>

#include <beluga/actions/assign.hpp>
#include <beluga/actions/normalize.hpp>
#include <cmath>
#include <execution>
#include <tuple>
#include <vector>

#include <range/v3/algorithm/equal.hpp>
#include "beluga/actions/normalize.hpp"
#include "beluga/primitives.hpp"

namespace {

Expand Down
16 changes: 12 additions & 4 deletions beluga/test/beluga/actions/test_propagate.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,14 +13,22 @@
// limitations under the License.

#include <gmock/gmock.h>
#include <gtest/gtest.h>

#include <beluga/actions/assign.hpp>
#include <beluga/actions/propagate.hpp>
#include <beluga/views/sample.hpp>
#include <execution>
#include <functional>
#include <tuple>
#include <vector>

#include <range/v3/algorithm/equal.hpp>
#include <range/v3/range/conversion.hpp>
#include <range/v3/view/take_exactly.hpp>

#include "beluga/actions/assign.hpp"
#include "beluga/actions/propagate.hpp"
#include "beluga/primitives.hpp"
#include "beluga/views/particles.hpp"
#include "beluga/views/sample.hpp"

namespace {

TEST(PropagateAction, DefaultExecutionPolicy) {
Expand Down
14 changes: 11 additions & 3 deletions beluga/test/beluga/actions/test_reweight.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,13 +13,21 @@
// limitations under the License.

#include <gmock/gmock.h>
#include <gtest/gtest.h>

#include <beluga/actions/assign.hpp>
#include <beluga/actions/reweight.hpp>
#include <execution>
#include <functional>
#include <tuple>
#include <vector>

#include <range/v3/algorithm/equal.hpp>
#include <range/v3/range/conversion.hpp>
#include <range/v3/view/intersperse.hpp>

#include "beluga/actions/assign.hpp"
#include "beluga/actions/reweight.hpp"
#include "beluga/primitives.hpp"
#include "beluga/views/particles.hpp"

namespace {

TEST(ReweightAction, DefaultExecutionPolicy) {
Expand Down
Loading

0 comments on commit 4b3cd5f

Please sign in to comment.