Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add clang tidy #5

Merged
merged 23 commits into from
Oct 4, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
23 commits
Select commit Hold shift + click to select a range
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
43 changes: 21 additions & 22 deletions .clang-tidy
Original file line number Diff line number Diff line change
@@ -1,26 +1,25 @@
---
# This was copied over from the moveit_studio repository.
#
# TODO(henningkayser): Re-enable performance-unnecessary-value-param once #214 is resolved
Checks: '-*,
performance-*,
-performance-unnecessary-value-param,
llvm-namespace-comment,
modernize-redundant-void-arg,
modernize-use-nullptr,
modernize-use-default,
modernize-use-override,
modernize-loop-convert,
readability-braces-around-statements,
readability-named-parameter,
readability-redundant-smartptr-get,
readability-redundant-string-cstr,
readability-simplify-boolean-expr,
readability-container-size-empty,
readability-identifier-naming,
'
Checks: -*,
bugprone-*,
clang-analyzer-*,
concurrency-*,
cppcoreguidelines-*,
google-*,
misc-*,
modernize-*,
performance-*,
portability-*,
readability-*,
-bugprone-easily-swappable-parameters,
-bugprone-exception-escape,
-cppcoreguidelines-avoid-magic-numbers,
-google-readability-casting,
-modernize-use-trailing-return-type,
-readability-identifier-length,
-readability-function-cognitive-complexity,
-readability-magic-numbers,
-readability-uppercase-literal-suffix,
-cppcoreguidelines-pro-type-vararg,
HeaderFilterRegex: ''
AnalyzeTemporaryDtors: false
CheckOptions:
Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

No longer a valid option in clang tidy 18

- key: llvm-namespace-comment.ShortNamespaceLines
value: '10'
Expand Down
25 changes: 25 additions & 0 deletions .github/workflows/ci.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -70,3 +70,28 @@ jobs:
if: always()
run: colcon test-result --verbose
working-directory: /colcon_ws

clang_tidy:
needs:
# Ensure the test job runs after the build job finishes instead of attempting to run in parallel
- build-ws
name: clang-tidy
runs-on: ubuntu-24.04
container:
# Run on the Docker image we tagged and pushed to a private repo in the job above
image: ghcr.io/picknikrobotics/fuse:${{ github.run_id }}
steps:
- name: Changed Files
id: changed-cpp-files
uses: tj-actions/[email protected]
with:
# Avoid using single or double quotes for multiline patterns
files: |
**.cpp
**.hpp
- run: run-clang-tidy -j $(nproc --all) -p build/ -export-fixes clang-tidy-fixes.yaml -config-file src/fuse/.clang-tidy ${{ steps.changed-cpp-files.outputs.all_changed_files }}
working-directory: /colcon_ws
- uses: asarium/[email protected]
with:
fixesFile: /colcon_ws/clang-tidy-fixes.yaml
noFailOnIssue: false
File renamed without changes.
15 changes: 0 additions & 15 deletions .github/workflows/ros2.yml

This file was deleted.

3 changes: 3 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -33,3 +33,6 @@

# Python compiled bytecode files
*.pyc

# clang tidy fixes
clang-tidy-fixes.yaml
20 changes: 0 additions & 20 deletions Jenkinsfile

This file was deleted.

41 changes: 24 additions & 17 deletions fuse_core/test/launch_tests/test_parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,12 +33,18 @@
*/
#include <gtest/gtest.h>

#include <numeric>
#include <exception>
#include <memory>
#include <rclcpp/exceptions/exceptions.hpp>
#include <rclcpp/executors/single_threaded_executor.hpp>
#include <rclcpp/node.hpp>
#include <rclcpp/utilities.hpp>
#include <stdexcept>
#include <string>
#include <thread>

#include <fuse_core/parameter.hpp>
#include <rclcpp/rclcpp.hpp>
#include "fuse_core/eigen.hpp"

class TestParameters : public ::testing::Test
{
Expand All @@ -59,6 +65,7 @@ class TestParameters : public ::testing::Test
executor_.reset();
}

private:
std::thread spinner_; //!< Internal thread for spinning the executor
rclcpp::executors::SingleThreadedExecutor::SharedPtr executor_;
};
Expand Down Expand Up @@ -102,15 +109,15 @@ TEST_F(TestParameters, getPositiveParam)
TEST_F(TestParameters, GetCovarianceDiagonalParam)
{
// Build expected covariance matrix:
constexpr int Size = 3;
constexpr int size = 3;
constexpr double variance = 1.0e-3;
constexpr double default_variance = 0.0;
constexpr double defaultVariance = 0.0;

fuse_core::Matrix3d expected_covariance = fuse_core::Matrix3d::Identity();
expected_covariance *= variance;

fuse_core::Matrix3d default_covariance = fuse_core::Matrix3d::Identity();
default_covariance *= default_variance;
default_covariance *= defaultVariance;

auto node = rclcpp::Node::make_shared("test_parameters_node");

Expand All @@ -123,10 +130,10 @@ TEST_F(TestParameters, GetCovarianceDiagonalParam)

try
{
const auto covariance = fuse_core::getCovarianceDiagonalParam<Size>(*node, parameter_name, default_variance);
const auto covariance = fuse_core::getCovarianceDiagonalParam<size>(*node, parameter_name, defaultVariance);

EXPECT_EQ(Size, covariance.rows());
EXPECT_EQ(Size, covariance.cols());
EXPECT_EQ(size, covariance.rows());
EXPECT_EQ(size, covariance.cols());

EXPECT_EQ(expected_covariance.rows() * expected_covariance.cols(),
expected_covariance.cwiseEqual(covariance).count())
Expand All @@ -148,10 +155,10 @@ TEST_F(TestParameters, GetCovarianceDiagonalParam)

try
{
const auto covariance = fuse_core::getCovarianceDiagonalParam<Size>(*node, parameter_name, default_variance);
const auto covariance = fuse_core::getCovarianceDiagonalParam<size>(*node, parameter_name, defaultVariance);

EXPECT_EQ(Size, covariance.rows());
EXPECT_EQ(Size, covariance.cols());
EXPECT_EQ(size, covariance.rows());
EXPECT_EQ(size, covariance.cols());

EXPECT_EQ(default_covariance.rows() * default_covariance.cols(), default_covariance.cwiseEqual(covariance).count())
<< "Expected\n"
Expand All @@ -170,7 +177,7 @@ TEST_F(TestParameters, GetCovarianceDiagonalParam)

ASSERT_FALSE(node->has_parameter(parameter_name));

EXPECT_THROW(fuse_core::getCovarianceDiagonalParam<Size>(*node, parameter_name, default_variance),
EXPECT_THROW(fuse_core::getCovarianceDiagonalParam<size>(*node, parameter_name, defaultVariance),
std::invalid_argument);
}

Expand All @@ -180,7 +187,7 @@ TEST_F(TestParameters, GetCovarianceDiagonalParam)

ASSERT_FALSE(node->has_parameter(parameter_name));

EXPECT_THROW(fuse_core::getCovarianceDiagonalParam<Size>(*node, parameter_name, default_variance),
EXPECT_THROW(fuse_core::getCovarianceDiagonalParam<size>(*node, parameter_name, defaultVariance),
std::invalid_argument);
}

Expand All @@ -190,7 +197,7 @@ TEST_F(TestParameters, GetCovarianceDiagonalParam)

ASSERT_FALSE(node->has_parameter(parameter_name));

EXPECT_THROW(fuse_core::getCovarianceDiagonalParam<Size>(*node, parameter_name, default_variance),
EXPECT_THROW(fuse_core::getCovarianceDiagonalParam<size>(*node, parameter_name, defaultVariance),
std::invalid_argument);
}

Expand All @@ -200,7 +207,7 @@ TEST_F(TestParameters, GetCovarianceDiagonalParam)
const std::string parameter_name{ "covariance_diagonal_with_strings" };

ASSERT_FALSE(node->has_parameter(parameter_name));
EXPECT_THROW(fuse_core::getCovarianceDiagonalParam<Size>(*node, parameter_name, default_variance),
EXPECT_THROW(fuse_core::getCovarianceDiagonalParam<size>(*node, parameter_name, defaultVariance),
rclcpp::exceptions::InvalidParameterTypeException);

// NOTE(CH3): A covariance diagonal with invalid element type used to not throw, and used to
Expand All @@ -217,7 +224,7 @@ TEST_F(TestParameters, GetCovarianceDiagonalParam)
const std::string parameter_name{ "covariance_diagonal_with_string" };

ASSERT_FALSE(node->has_parameter(parameter_name));
EXPECT_THROW(fuse_core::getCovarianceDiagonalParam<Size>(*node, parameter_name, default_variance),
EXPECT_THROW(fuse_core::getCovarianceDiagonalParam<size>(*node, parameter_name, defaultVariance),
rclcpp::exceptions::InvalidParameterTypeException);

// NOTE(CH3): A covariance diagonal with invalid element type used to not throw, and used to
Expand All @@ -234,7 +241,7 @@ int main(int argc, char** argv)
{
rclcpp::init(argc, argv);
testing::InitGoogleTest(&argc, argv);
int ret = RUN_ALL_TESTS();
int const ret = RUN_ALL_TESTS();
rclcpp::shutdown();
return ret;
}
4 changes: 4 additions & 0 deletions run_clang_tidy.bash
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
#!/bin/bash

# -j $(nproc --all) runs with all cores, but the prepended nice runs with a low priority so it won't make your computer unusable while clang tidy is going. The "$@" at the end passes all the filenames from pre-commit so it should only look for clang tidy fixes in the files you directly changed in the commit that is being checked.
nice run-clang-tidy -p ../../build_dbg -j $(nproc --all) -quiet -fix "$@"
Loading