Skip to content

Commit

Permalink
Fix clang-tidy-17 errors (#1122)
Browse files Browse the repository at this point in the history
  • Loading branch information
Levi-Armstrong authored Feb 12, 2025
1 parent a553b90 commit a5fed1a
Show file tree
Hide file tree
Showing 90 changed files with 356 additions and 339 deletions.
16 changes: 16 additions & 0 deletions .clang-tidy
Original file line number Diff line number Diff line change
Expand Up @@ -3,8 +3,10 @@ Checks: >
-*,
clang-diagnostic-*,
-clang-diagnostic-unknown-warning-option,
-clang-diagnostic-enum-constexpr-conversion,
clang-analyzer-*,
-clang-analyzer-cplusplus*,
-clang-analyzer-optin.core.EnumCastOutOfRange,
bugprone-*,
-bugprone-easily-swappable-parameters,
-bugprone-exception-escape,
Expand All @@ -21,9 +23,14 @@ Checks: >
misc-*,
-misc-non-private-member-variables-in-classes,
-misc-no-recursion,
-misc-const-correctness,
-misc-include-cleaner,
-misc-use-internal-linkage,
-misc-use-anonymous-namespace,
modernize-*,
-modernize-use-trailing-return-type,
-modernize-use-nodiscard,
-modernize-type-traits,
performance-*,
readability-*,
-readability-braces-around-statements,
Expand All @@ -38,8 +45,10 @@ WarningsAsErrors: >
-*,
clang-diagnostic-*,
-clang-diagnostic-unknown-warning-option,
-clang-diagnostic-enum-constexpr-conversion,
clang-analyzer-*,
-clang-analyzer-cplusplus*,
-clang-analyzer-optin.core.EnumCastOutOfRange,
bugprone-*,
-bugprone-easily-swappable-parameters,
-bugprone-exception-escape,
Expand All @@ -56,9 +65,14 @@ WarningsAsErrors: >
misc-*,
-misc-non-private-member-variables-in-classes,
-misc-no-recursion,
-misc-const-correctness,
-misc-include-cleaner,
-misc-use-internal-linkage,
-misc-use-anonymous-namespace,
modernize-*,
-modernize-use-trailing-return-type,
-modernize-use-nodiscard,
-modernize-type-traits,
performance-*,
readability-*,
-readability-braces-around-statements,
Expand All @@ -80,4 +94,6 @@ CheckOptions:
value: '1'
- key: cppcoreguidelines-pro-type-member-init.IgnoreArrays
value: '1'
ExtraArgs:
- '-std=c++17'
...
16 changes: 11 additions & 5 deletions .github/workflows/code_quality.yml
Original file line number Diff line number Diff line change
Expand Up @@ -24,12 +24,12 @@ jobs:
include:
- job_type: clang-tidy
env:
TARGET_CMAKE_ARGS: "-DCMAKE_CXX_COMPILER_LAUNCHER=ccache -DCMAKE_BUILD_TYPE=Debug -DTESSERACT_ENABLE_CLANG_TIDY=ON -DTESSERACT_ENABLE_TESTING=ON"
TARGET_CMAKE_ARGS: "-DCMAKE_CXX_COMPILER_LAUNCHER=ccache -DCMAKE_BUILD_TYPE=Debug -DTESSERACT_ENABLE_CLANG_TIDY=ON -DTESSERACT_ENABLE_TESTING=ON -DCLANG_TIDY_NAMES=clang-tidy-17"
- job_type: codecov
env:
TARGET_CMAKE_ARGS: "-DCMAKE_CXX_COMPILER_LAUNCHER=ccache -DCMAKE_BUILD_TYPE=Debug -DTESSERACT_ENABLE_CODE_COVERAGE=ON -DTESSERACT_WARNINGS_AS_ERRORS=OFF"
container:
image: ubuntu:20.04
image: ubuntu:22.04
env:
CCACHE_DIR: "$GITHUB_WORKSPACE/${{ matrix.job_type }}/.ccache"
DEBIAN_FRONTEND: noninteractive
Expand All @@ -45,14 +45,20 @@ jobs:
run: |
apt update
apt upgrade -y
apt install -y clang-tidy liboctomap-dev
apt install -y wget liboctomap-dev
echo "deb http://apt.llvm.org/jammy/ llvm-toolchain-jammy-17 main" | tee /etc/apt/sources.list.d/llvm-toolchain.list
echo "deb-src http://apt.llvm.org/jammy/ llvm-toolchain-jammy-17 main" | tee -a /etc/apt/sources.list.d/llvm-toolchain.list
wget -O - https://apt.llvm.org/llvm-snapshot.gpg.key | tee /etc/apt/trusted.gpg.d/llvm.asc
apt update -y
apt install -y clang-tidy-17 libomp-17-dev
- name: Build and Tests
uses: tesseract-robotics/colcon-action@v1
uses: tesseract-robotics/colcon-action@v11
with:
ccache-prefix: ${{ matrix.distro }}
vcs-file: dependencies_focal.repos
vcs-file: dependencies.repos
run-tests: false
rosdep-install-args: -iry --skip-keys=libomp-dev
upstream-args: --cmake-args -DCMAKE_BUILD_TYPE=Release
target-path: target_ws/src
target-args: --cmake-args ${{ matrix.env.TARGET_CMAKE_ARGS }}
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/nightly.yml
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ jobs:
apt install -y liboctomap-dev
- name: Build and Tests
uses: tesseract-robotics/colcon-action@v1
uses: tesseract-robotics/colcon-action@v11
with:
ccache-prefix: ${{ matrix.distro }}
vcs-file: dependencies.repos
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/package_debian.yml
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ jobs:
apt install -y liboctomap-dev
- name: Build and test
uses: tesseract-robotics/colcon-action@v9
uses: tesseract-robotics/colcon-action@v11
with:
ccache-enabled: false
vcs-file: ${{ matrix.distro == 'focal' && 'dependencies_focal.repos' || 'dependencies.repos' }}
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/ubuntu.yml
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ jobs:
apt install -y liboctomap-dev
- name: Build and Tests
uses: tesseract-robotics/colcon-action@v8
uses: tesseract-robotics/colcon-action@v11
with:
ccache-prefix: ${{ matrix.distro }}
vcs-file: ${{ matrix.distro == 'focal' && 'dependencies_focal.repos' || 'dependencies.repos' }}
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/windows.yml
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ jobs:
echo "CMAKE_PREFIX_PATH=$GITHUB_WORKSPACE\vcpkg\installed\x64-windows-release" >> "$GITHUB_ENV"
- name: Build and Tests
uses: tesseract-robotics/colcon-action@v1
uses: tesseract-robotics/colcon-action@v11
with:
ccache-prefix: ${{ matrix.distro }}
vcs-file: .github/workflows/windows_dependencies.repos
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/windows_dependencies.repos
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
- git:
local-name: ros_industrial_cmake_boilerplate
uri: https://github.com/ros-industrial/ros_industrial_cmake_boilerplate.git
version: 0.7.2
version: 0.7.3
- git:
local-name: opw_kinematics
uri: https://github.com/Jmeyer1292/opw_kinematics.git
Expand Down
2 changes: 1 addition & 1 deletion dependencies.repos
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
- git:
local-name: ros_industrial_cmake_boilerplate
uri: https://github.com/ros-industrial/ros_industrial_cmake_boilerplate.git
version: 0.7.2
version: 0.7.3
- git:
local-name: opw_kinematics
uri: https://github.com/Jmeyer1292/opw_kinematics.git
Expand Down
2 changes: 1 addition & 1 deletion dependencies_focal.repos
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
- git:
local-name: ros_industrial_cmake_boilerplate
uri: https://github.com/ros-industrial/ros_industrial_cmake_boilerplate.git
version: 0.7.2
version: 0.7.3
- git:
local-name: opw_kinematics
uri: https://github.com/Jmeyer1292/opw_kinematics.git
Expand Down
2 changes: 1 addition & 1 deletion dependencies_with_ext.repos
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
- git:
local-name: ros_industrial_cmake_boilerplate
uri: https://github.com/ros-industrial/ros_industrial_cmake_boilerplate.git
version: 0.7.2
version: 0.7.3
- git:
local-name: tesseract_ext
uri: https://github.com/ros-industrial-consortium/tesseract_ext.git
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -74,9 +74,9 @@ class BulletCollisionShapeCache

private:
/** @brief The static cache */
static std::map<boost::uuids::uuid, std::weak_ptr<BulletCollisionShape>> cache_;
static std::map<boost::uuids::uuid, std::weak_ptr<BulletCollisionShape>> cache_; // NOLINT
/** @brief The shared mutex for thread safety */
static std::mutex mutex_;
static std::mutex mutex_; // NOLINT
};
} // namespace tesseract_collision::tesseract_collision_bullet

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -140,11 +140,11 @@ class CollisionObjectWrapper : public btCollisionObject
/** @brief A user defined type id */
int m_type_id{ -1 };
/* @brief The shapes that define the collision object */
CollisionShapesConst m_shapes{};
CollisionShapesConst m_shapes;
/**< @brief The shapes poses information */
tesseract_common::VectorIsometry3d m_shape_poses{};
tesseract_common::VectorIsometry3d m_shape_poses;
/** @brief This manages the collision shape pointer so they get destroyed */
std::vector<std::shared_ptr<BulletCollisionShape>> m_data{};
std::vector<std::shared_ptr<BulletCollisionShape>> m_data;
};

using COW = CollisionObjectWrapper;
Expand Down Expand Up @@ -250,7 +250,8 @@ btScalar addCastSingleResult(btManifoldPoint& cp,
/** @brief This is copied directly out of BulletWorld */
struct TesseractBridgedManifoldResult : public btManifoldResult
{
btCollisionWorld::ContactResultCallback& m_resultCallback;
btCollisionWorld::ContactResultCallback&
m_resultCallback; // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)

TesseractBridgedManifoldResult(const btCollisionObjectWrapper* obj0Wrap,
const btCollisionObjectWrapper* obj1Wrap,
Expand All @@ -262,7 +263,7 @@ struct TesseractBridgedManifoldResult : public btManifoldResult
/** @brief The BroadphaseContactResultCallback is used to report contact points */
struct BroadphaseContactResultCallback
{
ContactTestData& collisions_;
ContactTestData& collisions_; // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
double contact_distance_;
bool verbose_;

Expand Down Expand Up @@ -313,7 +314,7 @@ struct CastBroadphaseContactResultCallback : public BroadphaseContactResultCallb

struct TesseractBroadphaseBridgedManifoldResult : public btManifoldResult
{
BroadphaseContactResultCallback& result_callback_;
BroadphaseContactResultCallback& result_callback_; // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)

TesseractBroadphaseBridgedManifoldResult(const btCollisionObjectWrapper* obj0Wrap,
const btCollisionObjectWrapper* obj1Wrap,
Expand All @@ -330,9 +331,9 @@ struct TesseractBroadphaseBridgedManifoldResult : public btManifoldResult
*/
class TesseractCollisionPairCallback : public btOverlapCallback
{
const btDispatcherInfo& dispatch_info_;
const btDispatcherInfo& dispatch_info_; // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
btCollisionDispatcher* dispatcher_;
BroadphaseContactResultCallback& results_callback_;
BroadphaseContactResultCallback& results_callback_; // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)

public:
TesseractCollisionPairCallback(const btDispatcherInfo& dispatchInfo,
Expand Down Expand Up @@ -382,8 +383,8 @@ COW::Ptr createCollisionObject(const std::string& name,

struct DiscreteCollisionCollector : public btCollisionWorld::ContactResultCallback
{
ContactTestData& collisions_;
const COW::Ptr cow_;
ContactTestData& collisions_; // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
const COW::Ptr cow_; // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
double contact_distance_;
bool verbose_;

Expand All @@ -405,8 +406,8 @@ struct DiscreteCollisionCollector : public btCollisionWorld::ContactResultCallba

struct CastCollisionCollector : public btCollisionWorld::ContactResultCallback
{
ContactTestData& collisions_;
const COW::Ptr cow_;
ContactTestData& collisions_; // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
const COW::Ptr cow_; // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members)
double contact_distance_;
bool verbose_;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -107,7 +107,7 @@ class TesseractCompoundCollisionAlgorithm : public btActivatingCollisionAlgorith
const btCollisionObjectWrapper* body1Wrap) override
{
void* mem = ci.m_dispatcher1->allocateCollisionAlgorithm(sizeof(TesseractCompoundCollisionAlgorithm));
return new (mem) TesseractCompoundCollisionAlgorithm(ci, body0Wrap, body1Wrap, false);
return new (mem) TesseractCompoundCollisionAlgorithm(ci, body0Wrap, body1Wrap, false); // NOLINT
}
};

Expand All @@ -118,7 +118,7 @@ class TesseractCompoundCollisionAlgorithm : public btActivatingCollisionAlgorith
const btCollisionObjectWrapper* body1Wrap) override
{
void* mem = ci.m_dispatcher1->allocateCollisionAlgorithm(sizeof(TesseractCompoundCollisionAlgorithm));
return new (mem) TesseractCompoundCollisionAlgorithm(ci, body0Wrap, body1Wrap, true);
return new (mem) TesseractCompoundCollisionAlgorithm(ci, body0Wrap, body1Wrap, true); // NOLINT
}
};
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -93,7 +93,7 @@ class TesseractCompoundCompoundCollisionAlgorithm : public TesseractCompoundColl
const btCollisionObjectWrapper* body1Wrap) override
{
void* mem = ci.m_dispatcher1->allocateCollisionAlgorithm(sizeof(TesseractCompoundCompoundCollisionAlgorithm));
return new (mem) TesseractCompoundCompoundCollisionAlgorithm(ci, body0Wrap, body1Wrap, false);
return new (mem) TesseractCompoundCompoundCollisionAlgorithm(ci, body0Wrap, body1Wrap, false); // NOLINT
}
};

Expand All @@ -104,7 +104,7 @@ class TesseractCompoundCompoundCollisionAlgorithm : public TesseractCompoundColl
const btCollisionObjectWrapper* body1Wrap) override
{
void* mem = ci.m_dispatcher1->allocateCollisionAlgorithm(sizeof(TesseractCompoundCompoundCollisionAlgorithm));
return new (mem) TesseractCompoundCompoundCollisionAlgorithm(ci, body0Wrap, body1Wrap, true);
return new (mem) TesseractCompoundCompoundCollisionAlgorithm(ci, body0Wrap, body1Wrap, true); // NOLINT
}
};
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -132,6 +132,7 @@ class TesseractConvexConvexAlgorithm : public btActivatingCollisionAlgorithm
const btCollisionObjectWrapper* body1Wrap) override
{
void* mem = ci.m_dispatcher1->allocateCollisionAlgorithm(sizeof(TesseractConvexConvexAlgorithm));
// NOLINTNEXTLINE
return new (mem) TesseractConvexConvexAlgorithm(ci.m_manifold,
ci,
body0Wrap,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,9 @@
namespace tesseract_collision::tesseract_collision_bullet
{
// Static member definitions
// NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables)
std::map<boost::uuids::uuid, std::weak_ptr<BulletCollisionShape>> BulletCollisionShapeCache::cache_;
// NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables)
std::mutex BulletCollisionShapeCache::mutex_;

BulletCollisionShape::BulletCollisionShape(std::shared_ptr<btCollisionShape> top_level_)
Expand Down
2 changes: 1 addition & 1 deletion tesseract_collision/bullet/src/bullet_factories.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ namespace tesseract_collision::tesseract_collision_bullet
TesseractCollisionConfigurationInfo getConfigInfo(const YAML::Node& config)
{
if (config.IsNull())
return TesseractCollisionConfigurationInfo();
return {};

bool share_pool_allocators{ false };
if (YAML::Node n = config["share_pool_allocators"])
Expand Down
27 changes: 13 additions & 14 deletions tesseract_collision/bullet/src/bullet_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -127,23 +127,23 @@ std::shared_ptr<BulletCollisionShape> createShapePrimitive(const tesseract_geome

std::shared_ptr<BulletCollisionShape> createShapePrimitive(const tesseract_geometry::Cylinder::ConstPtr& geom)
{
auto r = static_cast<btScalar>(geom->getRadius());
auto l = static_cast<btScalar>(geom->getLength() / 2);
return std::make_shared<BulletCollisionShape>(std::make_shared<btCylinderShapeZ>(btVector3(r, r, l)));
auto radius = static_cast<btScalar>(geom->getRadius());
auto length = static_cast<btScalar>(geom->getLength() / 2);
return std::make_shared<BulletCollisionShape>(std::make_shared<btCylinderShapeZ>(btVector3(radius, radius, length)));
}

std::shared_ptr<BulletCollisionShape> createShapePrimitive(const tesseract_geometry::Cone::ConstPtr& geom)
{
auto r = static_cast<btScalar>(geom->getRadius());
auto l = static_cast<btScalar>(geom->getLength());
return std::make_shared<BulletCollisionShape>(std::make_shared<btConeShapeZ>(r, l));
auto radius = static_cast<btScalar>(geom->getRadius());
auto length = static_cast<btScalar>(geom->getLength());
return std::make_shared<BulletCollisionShape>(std::make_shared<btConeShapeZ>(radius, length));
}

std::shared_ptr<BulletCollisionShape> createShapePrimitive(const tesseract_geometry::Capsule::ConstPtr& geom)
{
auto r = static_cast<btScalar>(geom->getRadius());
auto l = static_cast<btScalar>(geom->getLength());
return std::make_shared<BulletCollisionShape>(std::make_shared<btCapsuleShapeZ>(r, l));
auto radius = static_cast<btScalar>(geom->getRadius());
auto length = static_cast<btScalar>(geom->getLength());
return std::make_shared<BulletCollisionShape>(std::make_shared<btCapsuleShapeZ>(radius, length));
}

std::shared_ptr<BulletCollisionShape> createShapePrimitive(const tesseract_geometry::Mesh::ConstPtr& geom)
Expand All @@ -156,8 +156,7 @@ std::shared_ptr<BulletCollisionShape> createShapePrimitive(const tesseract_geome
auto collision_shape = std::make_shared<BulletCollisionShape>();
if (vertice_count > 0 && triangle_count > 0)
{
auto compound =
std::make_shared<btCompoundShape>(BULLET_COMPOUND_USE_DYNAMIC_AABB, static_cast<int>(triangle_count));
auto compound = std::make_shared<btCompoundShape>(BULLET_COMPOUND_USE_DYNAMIC_AABB, triangle_count);
compound->setMargin(BULLET_MARGIN); // margin: compound. seems to have no
// effect when positive but has an
// effect when negative
Expand Down Expand Up @@ -233,12 +232,12 @@ std::shared_ptr<BulletCollisionShape> createShapePrimitive(const tesseract_geome
geomTrans.setIdentity();
geomTrans.setOrigin(btVector3(
static_cast<btScalar>(it.getX()), static_cast<btScalar>(it.getY()), static_cast<btScalar>(it.getZ())));
auto l = static_cast<btScalar>(size / 2.0);
auto length = static_cast<btScalar>(size / 2.0);

std::shared_ptr<btCollisionShape> childshape = managed_shapes.at(it.getDepth());
if (childshape == nullptr)
{
childshape = std::make_shared<btBoxShape>(btVector3(l, l, l));
childshape = std::make_shared<btBoxShape>(btVector3(length, length, length));
childshape->setMargin(BULLET_MARGIN);
managed_shapes.at(it.getDepth()) = childshape;
}
Expand Down Expand Up @@ -784,7 +783,7 @@ void calculateContinuousData(ContactResult* col,
assert(shape != nullptr);

// Get the start and final location of the shape
btTransform shape_tfWorld0 = cow->getWorldTransform();
const btTransform& shape_tfWorld0 = cow->getWorldTransform();
btTransform shape_tfWorld1 = cow->getWorldTransform() * shape->m_t01;

// Given the shapes final location calculate the links transform at the final location
Expand Down
Loading

0 comments on commit a5fed1a

Please sign in to comment.