From a5fed1a3ad0b898ad31129938c4264c6f74c4f9e Mon Sep 17 00:00:00 2001 From: Levi Armstrong Date: Wed, 12 Feb 2025 12:55:07 -0600 Subject: [PATCH] Fix clang-tidy-17 errors (#1122) --- .clang-tidy | 16 +++++ .github/workflows/code_quality.yml | 16 +++-- .github/workflows/nightly.yml | 2 +- .github/workflows/package_debian.yml | 2 +- .github/workflows/ubuntu.yml | 2 +- .github/workflows/windows.yml | 2 +- .github/workflows/windows_dependencies.repos | 2 +- dependencies.repos | 2 +- dependencies_focal.repos | 2 +- dependencies_with_ext.repos | 2 +- .../bullet/bullet_collision_shape_cache.h | 4 +- .../tesseract_collision/bullet/bullet_utils.h | 25 ++++---- .../tesseract_compound_collision_algorithm.h | 4 +- ...ct_compound_compound_collision_algorithm.h | 4 +- .../tesseract_convex_convex_algorithm.h | 1 + .../src/bullet_collision_shape_cache.cpp | 2 + .../bullet/src/bullet_factories.cpp | 2 +- .../bullet/src/bullet_utils.cpp | 27 ++++---- .../bullet/src/convex_decomposition_hacd.cpp | 16 ++--- .../bullet/src/create_convex_hull.cpp | 6 +- .../src/tesseract_collision_configuration.cpp | 8 +-- ...tesseract_compound_collision_algorithm.cpp | 12 ++-- ..._compound_compound_collision_algorithm.cpp | 7 ++- .../src/tesseract_convex_convex_algorithm.cpp | 25 +++----- .../src/tesseract_gjk_pair_detector.cpp | 4 +- .../include/tesseract_collision/core/fwd.h | 12 ++-- .../include/tesseract_collision/core/types.h | 10 +-- tesseract_collision/core/src/common.cpp | 2 +- .../src/contact_managers_plugin_factory.cpp | 2 +- tesseract_collision/core/src/types.cpp | 61 ++++++++----------- .../fcl/fcl_collision_geometry_cache.h | 4 +- .../tesseract_collision/fcl/fcl_utils.h | 2 +- .../fcl/src/fcl_collision_geometry_cache.cpp | 2 + .../test/collision_core_unit.cpp | 16 ++--- .../test/contact_managers_factory_unit.cpp | 16 ++--- .../collision_large_dataset_unit.hpp | 2 +- .../vhacd/src/convex_decomposition_vhacd.cpp | 24 ++++---- .../vhacd/src/create_convex_decomposition.cpp | 6 +- .../include/tesseract_common/class_loader.hpp | 2 - .../include/tesseract_common/clone_cache.h | 2 +- .../tesseract_common/collision_margin_data.h | 2 +- .../contact_allowed_validator.h | 2 +- .../include/tesseract_common/fwd.h | 4 +- .../include/tesseract_common/joint_state.h | 2 +- .../tesseract_common/plugin_loader.hpp | 11 ++-- .../include/tesseract_common/serialization.h | 2 +- .../include/tesseract_common/utils.h | 2 +- .../src/allowed_collision_matrix.cpp | 2 +- .../src/collision_margin_data.cpp | 5 +- tesseract_common/src/joint_state.cpp | 7 ++- tesseract_common/src/resource_locator.cpp | 2 +- tesseract_common/src/utils.cpp | 14 ++--- tesseract_common/test/plugin_loader_unit.cpp | 2 +- .../test/tesseract_common_unit.cpp | 6 +- .../commands/add_link_command.h | 1 - .../include/tesseract_environment/events.h | 7 ++- .../commands/change_joint_origin_command.cpp | 1 + .../commands/change_link_origin_command.cpp | 1 + tesseract_environment/src/environment.cpp | 2 +- tesseract_environment/src/utils.cpp | 19 +++--- .../include/tesseract_geometry/fwd.h | 6 +- .../include/tesseract_geometry/geometry.h | 3 +- .../include/tesseract_geometry/impl/capsule.h | 2 +- .../include/tesseract_geometry/impl/cone.h | 2 +- .../tesseract_geometry/impl/convex_mesh.h | 2 +- .../tesseract_geometry/impl/cylinder.h | 2 +- .../include/tesseract_geometry/impl/octree.h | 2 +- .../include/tesseract_geometry/mesh_parser.h | 18 +++--- tesseract_geometry/src/geometries/capsule.cpp | 2 +- tesseract_geometry/src/geometries/cone.cpp | 2 +- .../src/geometries/cylinder.cpp | 2 +- tesseract_geometry/src/geometry.cpp | 1 - .../include/tesseract_kinematics/core/utils.h | 6 +- .../core/src/kinematic_group.cpp | 1 + .../core/src/kinematics_plugin_factory.cpp | 2 +- tesseract_kinematics/core/src/utils.cpp | 2 +- tesseract_kinematics/core/src/validate.cpp | 23 +++---- tesseract_kinematics/opw/src/opw_inv_kin.cpp | 2 +- tesseract_kinematics/ur/src/ur_inv_kin.cpp | 2 +- .../include/tesseract_scene_graph/fwd.h | 4 +- .../include/tesseract_scene_graph/graph.h | 10 +-- .../include/tesseract_scene_graph/joint.h | 2 +- tesseract_scene_graph/src/graph.cpp | 31 ++++++---- tesseract_scene_graph/src/kdl_parser.cpp | 8 ++- .../test/tesseract_scene_graph_unit.cpp | 50 +++++++-------- tesseract_srdf/test/tesseract_srdf_unit.cpp | 7 +-- .../src/ofkt_state_solver.cpp | 4 +- tesseract_urdf/CMakeLists.txt | 21 +++---- .../test/tesseract_urdf_urdf_unit.cpp | 2 +- .../tesseract_ignition_visualization.cpp | 22 +++---- 90 files changed, 356 insertions(+), 339 deletions(-) diff --git a/.clang-tidy b/.clang-tidy index 830da525463..5cc110b6f6b 100644 --- a/.clang-tidy +++ b/.clang-tidy @@ -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, @@ -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, @@ -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, @@ -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, @@ -80,4 +94,6 @@ CheckOptions: value: '1' - key: cppcoreguidelines-pro-type-member-init.IgnoreArrays value: '1' +ExtraArgs: + - '-std=c++17' ... diff --git a/.github/workflows/code_quality.yml b/.github/workflows/code_quality.yml index f5043806f3c..a801ef94385 100644 --- a/.github/workflows/code_quality.yml +++ b/.github/workflows/code_quality.yml @@ -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 @@ -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 }} diff --git a/.github/workflows/nightly.yml b/.github/workflows/nightly.yml index cb5b0265c06..c209a68a004 100644 --- a/.github/workflows/nightly.yml +++ b/.github/workflows/nightly.yml @@ -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 diff --git a/.github/workflows/package_debian.yml b/.github/workflows/package_debian.yml index ccff3d584e0..722641b2e33 100644 --- a/.github/workflows/package_debian.yml +++ b/.github/workflows/package_debian.yml @@ -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' }} diff --git a/.github/workflows/ubuntu.yml b/.github/workflows/ubuntu.yml index 41289acf8af..b8a8df71083 100644 --- a/.github/workflows/ubuntu.yml +++ b/.github/workflows/ubuntu.yml @@ -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' }} diff --git a/.github/workflows/windows.yml b/.github/workflows/windows.yml index db01dee252c..526afd19f4f 100644 --- a/.github/workflows/windows.yml +++ b/.github/workflows/windows.yml @@ -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 diff --git a/.github/workflows/windows_dependencies.repos b/.github/workflows/windows_dependencies.repos index d848e146ffb..edaa947611b 100644 --- a/.github/workflows/windows_dependencies.repos +++ b/.github/workflows/windows_dependencies.repos @@ -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 diff --git a/dependencies.repos b/dependencies.repos index 564f8dde106..698b2ef6671 100644 --- a/dependencies.repos +++ b/dependencies.repos @@ -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 diff --git a/dependencies_focal.repos b/dependencies_focal.repos index 49fe01865b0..912a7c0a8b0 100644 --- a/dependencies_focal.repos +++ b/dependencies_focal.repos @@ -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 diff --git a/dependencies_with_ext.repos b/dependencies_with_ext.repos index 81d9df5b101..79ac827b5fb 100644 --- a/dependencies_with_ext.repos +++ b/dependencies_with_ext.repos @@ -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 diff --git a/tesseract_collision/bullet/include/tesseract_collision/bullet/bullet_collision_shape_cache.h b/tesseract_collision/bullet/include/tesseract_collision/bullet/bullet_collision_shape_cache.h index 4352462a716..7e309bed043 100644 --- a/tesseract_collision/bullet/include/tesseract_collision/bullet/bullet_collision_shape_cache.h +++ b/tesseract_collision/bullet/include/tesseract_collision/bullet/bullet_collision_shape_cache.h @@ -74,9 +74,9 @@ class BulletCollisionShapeCache private: /** @brief The static cache */ - static std::map> cache_; + static std::map> cache_; // NOLINT /** @brief The shared mutex for thread safety */ - static std::mutex mutex_; + static std::mutex mutex_; // NOLINT }; } // namespace tesseract_collision::tesseract_collision_bullet diff --git a/tesseract_collision/bullet/include/tesseract_collision/bullet/bullet_utils.h b/tesseract_collision/bullet/include/tesseract_collision/bullet/bullet_utils.h index 5f12998d6bd..29cf695a0d2 100644 --- a/tesseract_collision/bullet/include/tesseract_collision/bullet/bullet_utils.h +++ b/tesseract_collision/bullet/include/tesseract_collision/bullet/bullet_utils.h @@ -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> m_data{}; + std::vector> m_data; }; using COW = CollisionObjectWrapper; @@ -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, @@ -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_; @@ -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, @@ -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, @@ -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_; @@ -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_; diff --git a/tesseract_collision/bullet/include/tesseract_collision/bullet/tesseract_compound_collision_algorithm.h b/tesseract_collision/bullet/include/tesseract_collision/bullet/tesseract_compound_collision_algorithm.h index 23e220322b1..e71d74bedb7 100644 --- a/tesseract_collision/bullet/include/tesseract_collision/bullet/tesseract_compound_collision_algorithm.h +++ b/tesseract_collision/bullet/include/tesseract_collision/bullet/tesseract_compound_collision_algorithm.h @@ -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 } }; @@ -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 } }; }; diff --git a/tesseract_collision/bullet/include/tesseract_collision/bullet/tesseract_compound_compound_collision_algorithm.h b/tesseract_collision/bullet/include/tesseract_collision/bullet/tesseract_compound_compound_collision_algorithm.h index 64cef5691b9..829beb178c6 100644 --- a/tesseract_collision/bullet/include/tesseract_collision/bullet/tesseract_compound_compound_collision_algorithm.h +++ b/tesseract_collision/bullet/include/tesseract_collision/bullet/tesseract_compound_compound_collision_algorithm.h @@ -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 } }; @@ -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 } }; }; diff --git a/tesseract_collision/bullet/include/tesseract_collision/bullet/tesseract_convex_convex_algorithm.h b/tesseract_collision/bullet/include/tesseract_collision/bullet/tesseract_convex_convex_algorithm.h index d2775dcb5cc..4727e36a752 100644 --- a/tesseract_collision/bullet/include/tesseract_collision/bullet/tesseract_convex_convex_algorithm.h +++ b/tesseract_collision/bullet/include/tesseract_collision/bullet/tesseract_convex_convex_algorithm.h @@ -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, diff --git a/tesseract_collision/bullet/src/bullet_collision_shape_cache.cpp b/tesseract_collision/bullet/src/bullet_collision_shape_cache.cpp index 7e950870db8..db1e38ccd6c 100644 --- a/tesseract_collision/bullet/src/bullet_collision_shape_cache.cpp +++ b/tesseract_collision/bullet/src/bullet_collision_shape_cache.cpp @@ -32,7 +32,9 @@ namespace tesseract_collision::tesseract_collision_bullet { // Static member definitions +// NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables) std::map> BulletCollisionShapeCache::cache_; +// NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables) std::mutex BulletCollisionShapeCache::mutex_; BulletCollisionShape::BulletCollisionShape(std::shared_ptr top_level_) diff --git a/tesseract_collision/bullet/src/bullet_factories.cpp b/tesseract_collision/bullet/src/bullet_factories.cpp index 565f66f549b..57c951418c8 100644 --- a/tesseract_collision/bullet/src/bullet_factories.cpp +++ b/tesseract_collision/bullet/src/bullet_factories.cpp @@ -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"]) diff --git a/tesseract_collision/bullet/src/bullet_utils.cpp b/tesseract_collision/bullet/src/bullet_utils.cpp index 82e1d55875a..c036e9d73cf 100644 --- a/tesseract_collision/bullet/src/bullet_utils.cpp +++ b/tesseract_collision/bullet/src/bullet_utils.cpp @@ -127,23 +127,23 @@ std::shared_ptr createShapePrimitive(const tesseract_geome std::shared_ptr createShapePrimitive(const tesseract_geometry::Cylinder::ConstPtr& geom) { - auto r = static_cast(geom->getRadius()); - auto l = static_cast(geom->getLength() / 2); - return std::make_shared(std::make_shared(btVector3(r, r, l))); + auto radius = static_cast(geom->getRadius()); + auto length = static_cast(geom->getLength() / 2); + return std::make_shared(std::make_shared(btVector3(radius, radius, length))); } std::shared_ptr createShapePrimitive(const tesseract_geometry::Cone::ConstPtr& geom) { - auto r = static_cast(geom->getRadius()); - auto l = static_cast(geom->getLength()); - return std::make_shared(std::make_shared(r, l)); + auto radius = static_cast(geom->getRadius()); + auto length = static_cast(geom->getLength()); + return std::make_shared(std::make_shared(radius, length)); } std::shared_ptr createShapePrimitive(const tesseract_geometry::Capsule::ConstPtr& geom) { - auto r = static_cast(geom->getRadius()); - auto l = static_cast(geom->getLength()); - return std::make_shared(std::make_shared(r, l)); + auto radius = static_cast(geom->getRadius()); + auto length = static_cast(geom->getLength()); + return std::make_shared(std::make_shared(radius, length)); } std::shared_ptr createShapePrimitive(const tesseract_geometry::Mesh::ConstPtr& geom) @@ -156,8 +156,7 @@ std::shared_ptr createShapePrimitive(const tesseract_geome auto collision_shape = std::make_shared(); if (vertice_count > 0 && triangle_count > 0) { - auto compound = - std::make_shared(BULLET_COMPOUND_USE_DYNAMIC_AABB, static_cast(triangle_count)); + auto compound = std::make_shared(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 @@ -233,12 +232,12 @@ std::shared_ptr createShapePrimitive(const tesseract_geome geomTrans.setIdentity(); geomTrans.setOrigin(btVector3( static_cast(it.getX()), static_cast(it.getY()), static_cast(it.getZ()))); - auto l = static_cast(size / 2.0); + auto length = static_cast(size / 2.0); std::shared_ptr childshape = managed_shapes.at(it.getDepth()); if (childshape == nullptr) { - childshape = std::make_shared(btVector3(l, l, l)); + childshape = std::make_shared(btVector3(length, length, length)); childshape->setMargin(BULLET_MARGIN); managed_shapes.at(it.getDepth()) = childshape; } @@ -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 diff --git a/tesseract_collision/bullet/src/convex_decomposition_hacd.cpp b/tesseract_collision/bullet/src/convex_decomposition_hacd.cpp index 5c908d8414d..cbbab14b79a 100644 --- a/tesseract_collision/bullet/src/convex_decomposition_hacd.cpp +++ b/tesseract_collision/bullet/src/convex_decomposition_hacd.cpp @@ -102,14 +102,14 @@ ConvexDecompositionHACD::compute(const tesseract_common::VectorVector3d& vertice void HACDParameters::print() const { std::stringstream msg; - msg << "+ Parameters" << std::endl; - msg << "\t compacity_weight " << compacity_weight << std::endl; - msg << "\t volume_weight " << volume_weight << std::endl; - msg << "\t max. concavity " << concavity << std::endl; - msg << "\t min number of clusters " << min_num_clusters << std::endl; - msg << "\t add extra dist points " << ((add_extra_dist_points) ? "true" : "false") << std::endl; - msg << "\t add neighbours dist points " << ((add_neighbours_dist_points) ? "true" : "false") << std::endl; - msg << "\t add faces points " << ((add_faces_points) ? "true" : "false") << std::endl; + msg << "+ Parameters\n"; + msg << "\t compacity_weight " << compacity_weight << "\n"; + msg << "\t volume_weight " << volume_weight << "\n"; + msg << "\t max. concavity " << concavity << "\n"; + msg << "\t min number of clusters " << min_num_clusters << "\n"; + msg << "\t add extra dist points " << ((add_extra_dist_points) ? "true" : "false") << "\n"; + msg << "\t add neighbours dist points " << ((add_neighbours_dist_points) ? "true" : "false") << "\n"; + msg << "\t add faces points " << ((add_faces_points) ? "true" : "false") << "\n"; std::cout << msg.str(); } diff --git a/tesseract_collision/bullet/src/create_convex_hull.cpp b/tesseract_collision/bullet/src/create_convex_hull.cpp index 454aa0309ce..024e9a684db 100644 --- a/tesseract_collision/bullet/src/create_convex_hull.cpp +++ b/tesseract_collision/bullet/src/create_convex_hull.cpp @@ -71,7 +71,7 @@ int main(int argc, char** argv) /** --help option */ if (vm.count("help") != 0U) { - std::cout << "Basic Command Line Parameter App" << std::endl << desc << std::endl; + std::cout << "Basic Command Line Parameter App\n" << desc << "\n"; return SUCCESS; } @@ -80,8 +80,8 @@ int main(int argc, char** argv) } catch (po::error& e) { - std::cerr << "ERROR: " << e.what() << std::endl << std::endl; - std::cerr << desc << std::endl; + std::cerr << "ERROR: " << e.what() << "\n\n"; + std::cerr << desc << "\n"; return ERROR_IN_COMMAND_LINE; } diff --git a/tesseract_collision/bullet/src/tesseract_collision_configuration.cpp b/tesseract_collision/bullet/src/tesseract_collision_configuration.cpp index 558ffb24815..68ff6c05fc3 100644 --- a/tesseract_collision/bullet/src/tesseract_collision_configuration.cpp +++ b/tesseract_collision/bullet/src/tesseract_collision_configuration.cpp @@ -138,16 +138,16 @@ TesseractCollisionConfiguration::TesseractCollisionConfiguration(const Tesseract } mem = btAlignedAlloc(sizeof(TesseractConvexConvexAlgorithm::CreateFunc), 16); - m_convexConvexCreateFunc = new (mem) TesseractConvexConvexAlgorithm::CreateFunc(m_pdSolver); + m_convexConvexCreateFunc = new (mem) TesseractConvexConvexAlgorithm::CreateFunc(m_pdSolver); // NOLINT mem = btAlignedAlloc(sizeof(TesseractCompoundCollisionAlgorithm::CreateFunc), 16); - m_compoundCreateFunc = new (mem) TesseractCompoundCollisionAlgorithm::CreateFunc; + m_compoundCreateFunc = new (mem) TesseractCompoundCollisionAlgorithm::CreateFunc; // NOLINT mem = btAlignedAlloc(sizeof(TesseractCompoundCompoundCollisionAlgorithm::CreateFunc), 16); - m_compoundCompoundCreateFunc = new (mem) TesseractCompoundCompoundCollisionAlgorithm::CreateFunc; + m_compoundCompoundCreateFunc = new (mem) TesseractCompoundCompoundCollisionAlgorithm::CreateFunc; // NOLINT mem = btAlignedAlloc(sizeof(TesseractCompoundCollisionAlgorithm::SwappedCreateFunc), 16); - m_swappedCompoundCreateFunc = new (mem) TesseractCompoundCollisionAlgorithm::SwappedCreateFunc; + m_swappedCompoundCreateFunc = new (mem) TesseractCompoundCollisionAlgorithm::SwappedCreateFunc; // NOLINT } } // namespace tesseract_collision::tesseract_collision_bullet diff --git a/tesseract_collision/bullet/src/tesseract_compound_collision_algorithm.cpp b/tesseract_collision/bullet/src/tesseract_compound_collision_algorithm.cpp index 4ba7e3c72f7..472457fd2d5 100644 --- a/tesseract_collision/bullet/src/tesseract_compound_collision_algorithm.cpp +++ b/tesseract_collision/bullet/src/tesseract_compound_collision_algorithm.cpp @@ -110,7 +110,7 @@ struct TesseractCompoundLeafCallback : btDbvt::ICollide const btCollisionObjectWrapper* m_compoundColObjWrap; const btCollisionObjectWrapper* m_otherObjWrap; btDispatcher* m_dispatcher; - const btDispatcherInfo& m_dispatchInfo; + const btDispatcherInfo& m_dispatchInfo; // NOLINT btManifoldResult* m_resultOut; btCollisionAlgorithm** m_childCollisionAlgorithms; btPersistentManifold* m_sharedManifold; @@ -223,7 +223,7 @@ struct TesseractCompoundLeafCallback : btDbvt::ICollide algo->processCollision(&compoundWrap, m_otherObjWrap, m_dispatchInfo, m_resultOut); -#if 0 +#if 0 // NOLINT if (m_dispatchInfo.m_debugDraw && (m_dispatchInfo.m_debugDraw->getDebugMode() & btIDebugDraw::DBG_DrawAabb)) { btVector3 worldAabbMin,worldAabbMax; @@ -254,7 +254,7 @@ struct TesseractCompoundLeafCallback : btDbvt::ICollide const auto* compoundShape = static_cast(m_compoundColObjWrap->getCollisionShape()); const btCollisionShape* childShape = compoundShape->getChildShape(index); -#if 0 +#if 0 // NOLINT if (m_dispatchInfo.m_debugDraw && (m_dispatchInfo.m_debugDraw->getDebugMode() & btIDebugDraw::DBG_DrawAabb)) { btVector3 worldAabbMin,worldAabbMax; @@ -429,10 +429,8 @@ btScalar TesseractCompoundCollisionAlgorithm::calculateTimeOfImpact(btCollisionO // btCollisionShape* tmpShape = colObj->getCollisionShape(); // colObj->internalSetTemporaryCollisionShape( childShape ); btScalar frac = m_childCollisionAlgorithms[i]->calculateTimeOfImpact(colObj, otherObj, dispatchInfo, resultOut); - if (frac < hitFraction) - { - hitFraction = frac; - } + hitFraction = std::min(frac, hitFraction); + // revert back // colObj->internalSetTemporaryCollisionShape( tmpShape); colObj->setWorldTransform(orgTrans); diff --git a/tesseract_collision/bullet/src/tesseract_compound_compound_collision_algorithm.cpp b/tesseract_collision/bullet/src/tesseract_compound_compound_collision_algorithm.cpp index d0fffa290fa..fd4c2bd53e6 100644 --- a/tesseract_collision/bullet/src/tesseract_compound_compound_collision_algorithm.cpp +++ b/tesseract_collision/bullet/src/tesseract_compound_compound_collision_algorithm.cpp @@ -109,7 +109,7 @@ struct TesseractCompoundCompoundLeafCallback : btDbvt::ICollide const btCollisionObjectWrapper* m_compound0ColObjWrap; const btCollisionObjectWrapper* m_compound1ColObjWrap; btDispatcher* m_dispatcher; - const btDispatcherInfo& m_dispatchInfo; + const btDispatcherInfo& m_dispatchInfo; // NOLINT btManifoldResult* m_resultOut; class btHashedSimplePairCache* m_childCollisionAlgorithmCache; @@ -276,7 +276,7 @@ static inline void MycollideTT(const btDbvtNode* root0, stkStack.resize(btDbvt::DOUBLE_STACKSIZE); #endif stkStack[0] = btDbvt::sStkNN(root0, root1); - do + do // NOLINT(cppcoreguidelines-avoid-do-while) { btDbvt::sStkNN p = stkStack[--depth]; if (MyIntersect(p.a->volume, p.b->volume, xform, distanceThreshold)) @@ -335,7 +335,8 @@ void TesseractCompoundCompoundCollisionAlgorithm::processCollision(const btColli const btDbvt* tree1 = compoundShape1->getDynamicAabbTree(); if (tree0 == nullptr || tree1 == nullptr) { - return TesseractCompoundCollisionAlgorithm::processCollision(body0Wrap, body1Wrap, dispatchInfo, resultOut); + TesseractCompoundCollisionAlgorithm::processCollision(body0Wrap, body1Wrap, dispatchInfo, resultOut); + return; } /// btCompoundShape might have changed: ////make sure the internal child collision algorithm caches are still valid diff --git a/tesseract_collision/bullet/src/tesseract_convex_convex_algorithm.cpp b/tesseract_collision/bullet/src/tesseract_convex_convex_algorithm.cpp index f09f68b4ff7..a0c901c3e14 100644 --- a/tesseract_collision/bullet/src/tesseract_convex_convex_algorithm.cpp +++ b/tesseract_collision/bullet/src/tesseract_convex_convex_algorithm.cpp @@ -79,7 +79,7 @@ static SIMD_FORCE_INLINE void segmentsClosestPoints(btVector3& ptsVector, btScalar dirA_dot_trans = btDot(dirA, translation); btScalar dirB_dot_trans = btDot(dirB, translation); - btScalar denom = btScalar(1.0) - dirA_dot_dirB * dirA_dot_dirB; + btScalar denom = btScalar(1.0) - (dirA_dot_dirB * dirA_dot_dirB); if (denom == btScalar(0.0)) { @@ -611,7 +611,7 @@ void TesseractConvexConvexAlgorithm::processCollision(const btCollisionObjectWra if (useSatSepNormal) { -#if 0 +#if 0 // NOLINT if (0) { //initializePolyhedralFeatures performs a convex hull computation, not needed for a single triangle @@ -643,10 +643,7 @@ void TesseractConvexConvexAlgorithm::processCollision(const btCollisionObjectWra for (int v = 0; v < combinedFaceA.m_indices.size(); v++) { btScalar eq = tri->m_vertices1[combinedFaceA.m_indices[v]].dot(faceNormal); - if (planeEq > eq) - { - planeEq = eq; - } + planeEq = std::min(planeEq, eq); } combinedFaceA.m_plane[0] = faceNormal[0]; combinedFaceA.m_plane[1] = faceNormal[1]; @@ -665,10 +662,7 @@ void TesseractConvexConvexAlgorithm::processCollision(const btCollisionObjectWra for (int v = 0; v < combinedFaceB.m_indices.size(); v++) { btScalar eq = tri->m_vertices1[combinedFaceB.m_indices[v]].dot(faceNormal); - if (planeEq > eq) - { - planeEq = eq; - } + planeEq = std::min(planeEq, eq); } combinedFaceB.m_plane[0] = faceNormal[0]; @@ -720,7 +714,7 @@ void TesseractConvexConvexAlgorithm::processCollision(const btCollisionObjectWra // minDist = dummy.m_depth; foundSepAxis = true; } -#if 0 +#if 0 // NOLINT btScalar l2 = gjkPairDetector.getCachedSeparatingAxis().length2(); if (l2>SIMD_EPSILON) { @@ -789,8 +783,7 @@ void TesseractConvexConvexAlgorithm::processCollision(const btCollisionObjectWra perturbeAngle = gContactBreakingThreshold / radiusB; perturbeA = false; } - if (perturbeAngle > angleLimit) - perturbeAngle = angleLimit; + perturbeAngle = std::min(perturbeAngle, angleLimit); btTransform unPerturbedTransform; if (perturbeA) @@ -914,8 +907,7 @@ btScalar TesseractConvexConvexAlgorithm::calculateTimeOfImpact(btCollisionObject if (body1->getHitFraction() > result.m_fraction) body1->setHitFraction(result.m_fraction); - if (resultFraction > result.m_fraction) - resultFraction = result.m_fraction; + resultFraction = std::min(resultFraction, result.m_fraction); } } @@ -945,8 +937,7 @@ btScalar TesseractConvexConvexAlgorithm::calculateTimeOfImpact(btCollisionObject if (body1->getHitFraction() > result.m_fraction) body1->setHitFraction(result.m_fraction); - if (resultFraction > result.m_fraction) - resultFraction = result.m_fraction; + resultFraction = std::min(resultFraction, result.m_fraction); } } diff --git a/tesseract_collision/bullet/src/tesseract_gjk_pair_detector.cpp b/tesseract_collision/bullet/src/tesseract_gjk_pair_detector.cpp index f2a19963b70..2ae3fabc191 100644 --- a/tesseract_collision/bullet/src/tesseract_gjk_pair_detector.cpp +++ b/tesseract_collision/bullet/src/tesseract_gjk_pair_detector.cpp @@ -900,8 +900,8 @@ void TesseractGjkPairDetector::getClosestPointsNonVirtual(const ClosestPointInpu btScalar previousSquaredDistance = squaredDistance; squaredDistance = newCachedSeparatingAxis.length2(); -#if 0 - ///warning: this termination condition leads to some problems in 2d test case see Bullet/Demos/Box2dDemo +#if 0 // NOLINT + /// warning: this termination condition leads to some problems in 2d test case see Bullet/Demos/Box2dDemo if (squaredDistance > previousSquaredDistance) { m_degenerateSimplex = 7; diff --git a/tesseract_collision/core/include/tesseract_collision/core/fwd.h b/tesseract_collision/core/include/tesseract_collision/core/fwd.h index 253193a6cf8..79aaad23118 100644 --- a/tesseract_collision/core/include/tesseract_collision/core/fwd.h +++ b/tesseract_collision/core/include/tesseract_collision/core/fwd.h @@ -26,18 +26,20 @@ #ifndef TESSERACT_COLLISION_CORE_TESSERACT_COLLISION_FWD_H #define TESSERACT_COLLISION_CORE_TESSERACT_COLLISION_FWD_H +#include + namespace tesseract_collision { // types.h -enum class ContinuousCollisionType; -enum class ContactTestType; +enum class ContinuousCollisionType : std::uint8_t; +enum class ContactTestType : std::uint8_t; struct ContactResult; class ContactResultMap; struct ContactRequest; struct ContactTestData; -enum class CollisionEvaluatorType; -enum class CollisionCheckProgramType; -enum class ACMOverrideType; +enum class CollisionEvaluatorType : std::uint8_t; +enum class CollisionCheckProgramType : std::uint8_t; +enum class ACMOverrideType : std::uint8_t; struct ContactManagerConfig; struct CollisionCheckConfig; struct ContactTrajectorySubstepResults; diff --git a/tesseract_collision/core/include/tesseract_collision/core/types.h b/tesseract_collision/core/include/tesseract_collision/core/types.h index a51dcb94ff8..0789b926a6c 100644 --- a/tesseract_collision/core/include/tesseract_collision/core/types.h +++ b/tesseract_collision/core/include/tesseract_collision/core/types.h @@ -55,7 +55,7 @@ using PairsCollisionMarginData = class ContactResultValidator; -enum class ContinuousCollisionType +enum class ContinuousCollisionType : std::uint8_t { CCType_None, CCType_Time0, @@ -63,7 +63,7 @@ enum class ContinuousCollisionType CCType_Between }; -enum class ContactTestType +enum class ContactTestType : std::uint8_t { FIRST = 0, /**< Return at first contact for any pair of objects */ CLOSEST = 1, /**< Return the global minimum for a pair of objects */ @@ -360,7 +360,7 @@ struct ContactTestData * CONTINUOUS - Continuous contact manager using only steps specified * LVS_CONTINUOUS - Continuous contact manager interpolating using longest valid segment */ -enum class CollisionEvaluatorType +enum class CollisionEvaluatorType : std::uint8_t { /** @brief None */ NONE, @@ -375,7 +375,7 @@ enum class CollisionEvaluatorType }; /** @brief The mode used to check program */ -enum class CollisionCheckProgramType +enum class CollisionCheckProgramType : std::uint8_t { /** @brief Check all states */ ALL, @@ -393,7 +393,7 @@ enum class CollisionCheckProgramType /** @brief Identifies how the provided AllowedCollisionMatrix should be applied relative to the isAllowedFn in the * contact manager */ -enum class ACMOverrideType +enum class ACMOverrideType : std::uint8_t { /** @brief Do not apply AllowedCollisionMatrix */ NONE, diff --git a/tesseract_collision/core/src/common.cpp b/tesseract_collision/core/src/common.cpp index 812a25763ff..116a32c6211 100644 --- a/tesseract_collision/core/src/common.cpp +++ b/tesseract_collision/core/src/common.cpp @@ -374,7 +374,7 @@ int loadSimplePlyFile(const std::string& path, return 0; } - vertices.push_back(Eigen::Vector3d(std::stod(tokens[0]), std::stod(tokens[1]), std::stod(tokens[2]))); + vertices.emplace_back(std::stod(tokens[0]), std::stod(tokens[1]), std::stod(tokens[2])); } std::vector local_faces; diff --git a/tesseract_collision/core/src/contact_managers_plugin_factory.cpp b/tesseract_collision/core/src/contact_managers_plugin_factory.cpp index fade4cebce5..bb9ab8b65c3 100644 --- a/tesseract_collision/core/src/contact_managers_plugin_factory.cpp +++ b/tesseract_collision/core/src/contact_managers_plugin_factory.cpp @@ -32,7 +32,7 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP #include #include #include -#include +#include #include #include #include diff --git a/tesseract_collision/core/src/types.cpp b/tesseract_collision/core/src/types.cpp index eed2a650cb6..d4a2b6e5c1e 100644 --- a/tesseract_collision/core/src/types.cpp +++ b/tesseract_collision/core/src/types.cpp @@ -550,7 +550,7 @@ std::stringstream ContactTrajectoryResults::trajectoryCollisionResultsTable() co if (numContacts() == 0) { - ss << "No contacts detected" << std::endl; + ss << "No contacts detected\n"; return ss; } @@ -563,9 +563,8 @@ std::stringstream ContactTrajectoryResults::trajectoryCollisionResultsTable() co int longest_steps_width = 2 + static_cast(step_title.size()); int number_steps_digits = static_cast(std::log10(steps.back().step)) + 1; // *2 for either side, plus 1 for '/', plus 2 for spaces - int width_steps_display = number_steps_digits * 2 + 3; - if (width_steps_display > longest_steps_width) - longest_steps_width = width_steps_display; + int width_steps_display = (number_steps_digits * 2) + 3; + longest_steps_width = std::max(width_steps_display, longest_steps_width); step_details_width += longest_steps_width; @@ -573,10 +572,7 @@ std::stringstream ContactTrajectoryResults::trajectoryCollisionResultsTable() co std::string joint_name_title = "JOINT NAMES"; int longest_joint_name_width = static_cast(joint_name_title.size()) + 2; for (const auto& name : joint_names) - { - if (static_cast(name.size()) + 2 > longest_joint_name_width) - longest_joint_name_width = static_cast(name.size()) + 2; - } + longest_joint_name_width = std::max(static_cast(name.size()) + 2, longest_joint_name_width); step_details_width += longest_joint_name_width; @@ -596,9 +592,8 @@ std::stringstream ContactTrajectoryResults::trajectoryCollisionResultsTable() co state0_value *= -1; } int state0_number_digits_left_decimal = static_cast(std::log10(state0_value)) + 1; - if (state0_number_digits_left_decimal + 7 > longest_state0_width) - longest_state0_width = - state0_number_digits_left_decimal + 7; // + 4 after decimal + 2 for spaces either side + 1 for decimal + // + 4 after decimal + 2 for spaces either side + 1 for decimal + longest_state0_width = std::max(state0_number_digits_left_decimal + 7, longest_state0_width); double state1_value = step.state1(i); if (state1_value < 0) @@ -606,9 +601,8 @@ std::stringstream ContactTrajectoryResults::trajectoryCollisionResultsTable() co state1_value *= -1; } int state1_number_digits_left_decimal = static_cast(std::log10(state1_value)) + 1; - if (state1_number_digits_left_decimal + 7 > longest_state1_width) - longest_state1_width = - state1_number_digits_left_decimal + 7; // + 4 after decimal + 2 for spaces either side + 1 for decimal + // + 4 after decimal + 2 for spaces either side + 1 for decimal + longest_state1_width = std::max(state1_number_digits_left_decimal + 7, longest_state1_width); } } @@ -627,9 +621,8 @@ std::stringstream ContactTrajectoryResults::trajectoryCollisionResultsTable() co // Substep is displayed as (substep)/(total number of substeps), example: 5/7 // so length will be 2*(max substep width) + 1 int number_digits = static_cast(std::log10(step.substeps.size())) + 1; - int width = 2 * number_digits + 3; - if (width > longest_substep_width) - longest_substep_width = width; + int width = (2 * number_digits) + 3; + longest_substep_width = std::max(width, longest_substep_width); } substep_details_width += longest_substep_width; @@ -650,12 +643,10 @@ std::stringstream ContactTrajectoryResults::trajectoryCollisionResultsTable() co if (collision.second.empty()) continue; std::string link1_name = collision.second.front().link_names[0]; - if (static_cast(link1_name.size()) + 2 > longest_link1_width) - longest_link1_width = static_cast(link1_name.size()) + 2; + longest_link1_width = std::max(static_cast(link1_name.size()) + 2, longest_link1_width); std::string link2_name = collision.second.front().link_names[1]; - if (static_cast(link2_name.size()) + 2 > longest_link2_width) - longest_link2_width = static_cast(link2_name.size()) + 2; + longest_link2_width = std::max(static_cast(link2_name.size()) + 2, longest_link2_width); } } } @@ -680,15 +671,14 @@ std::stringstream ContactTrajectoryResults::trajectoryCollisionResultsTable() co // Start making the table // Start on new line to avoid offset by anythnig on previous line - ss << std::endl; + ss << "\n"; // Make the header ss << std::setw(longest_steps_width) << step_title << std::setw(longest_joint_name_width) << joint_name_title << std::setw(longest_state0_width) << state0_title << std::setw(longest_state1_width) << state1_title << "|" << std::setw(longest_substep_width) << substep_title << std::setw(longest_link1_width) << link1_title - << std::setw(longest_link2_width) << link2_title << std::setw(longest_distance_width) << distance_title - << std::endl; + << std::setw(longest_link2_width) << link2_title << std::setw(longest_distance_width) << distance_title << "\n"; - ss << new_step_string << std::endl; + ss << new_step_string << "\n"; for (const auto& step : steps) { @@ -741,7 +731,7 @@ std::stringstream ContactTrajectoryResults::trajectoryCollisionResultsTable() co ss << std::setw(longest_link1_width) << collision.second.front().link_names[0]; ss << std::setw(longest_link2_width) << collision.second.front().link_names[1]; ss << std::setw(longest_distance_width) << collision.second.front().distance; - ss << std::endl; + ss << "\n"; line_number++; } @@ -760,7 +750,7 @@ std::stringstream ContactTrajectoryResults::trajectoryCollisionResultsTable() co } ss << "|"; ss << new_substep_string; - ss << std::endl; + ss << "\n"; line_number++; } @@ -771,10 +761,10 @@ std::stringstream ContactTrajectoryResults::trajectoryCollisionResultsTable() co ss << std::setw(longest_joint_name_width) << joint_names[static_cast(line_number)]; ss << std::setw(longest_state0_width) << step.state0(line_number); ss << std::setw(longest_state1_width) << step.state1(line_number); - ss << "|" << std::endl; + ss << "|\n"; line_number++; } - ss << new_step_string << std::endl; + ss << new_step_string << "\n"; } return ss; } @@ -828,17 +818,14 @@ std::stringstream ContactTrajectoryResults::collisionFrequencyPerLink() const if (link_index_map.empty()) { - ss << "No contacts detected" << std::endl; + ss << "No contacts detected\n"; return ss; } // Determine the maximum width for the link name column std::size_t max_link_name_length = 0; for (const auto& entry : link_index_map) - { - if (entry.first.size() > max_link_name_length) - max_link_name_length = entry.first.size(); - } + max_link_name_length = std::max(entry.first.size(), max_link_name_length); // Adjust the width to have some extra space after the longest link name const int column_width = static_cast(max_link_name_length) + 2; @@ -850,7 +837,7 @@ std::stringstream ContactTrajectoryResults::collisionFrequencyPerLink() const { ss << std::setw(5) << i << "|"; } - ss << std::endl; + ss << "\n"; // Prepare the separator row ss << std::setw(column_width + 5) << " " @@ -860,7 +847,7 @@ std::stringstream ContactTrajectoryResults::collisionFrequencyPerLink() const ss << std::setw(5) << "-----" << "|"; } - ss << std::endl; + ss << "\n"; // Prepare the data rows std::vector link_names(link_index_map.size()); @@ -879,7 +866,7 @@ std::stringstream ContactTrajectoryResults::collisionFrequencyPerLink() const ss << std::setw(5) << collision_matrix[i][j] << "|"; } - ss << std::endl; + ss << "\n"; } return ss; diff --git a/tesseract_collision/fcl/include/tesseract_collision/fcl/fcl_collision_geometry_cache.h b/tesseract_collision/fcl/include/tesseract_collision/fcl/fcl_collision_geometry_cache.h index 260e0dcff30..19e64db1b17 100644 --- a/tesseract_collision/fcl/include/tesseract_collision/fcl/fcl_collision_geometry_cache.h +++ b/tesseract_collision/fcl/include/tesseract_collision/fcl/fcl_collision_geometry_cache.h @@ -64,9 +64,9 @@ class FCLCollisionGeometryCache private: /** @brief The static cache */ - static std::map> cache_; + static std::map> cache_; // NOLINT /** @brief The shared mutex for thread safety */ - static std::mutex mutex_; + static std::mutex mutex_; // NOLINT }; } // namespace tesseract_collision::tesseract_collision_fcl diff --git a/tesseract_collision/fcl/include/tesseract_collision/fcl/fcl_utils.h b/tesseract_collision/fcl/include/tesseract_collision/fcl/fcl_utils.h index 9ad71682ce2..0b3d61bdab7 100644 --- a/tesseract_collision/fcl/include/tesseract_collision/fcl/fcl_utils.h +++ b/tesseract_collision/fcl/include/tesseract_collision/fcl/fcl_utils.h @@ -62,7 +62,7 @@ using CollisionObjectPtr = std::shared_ptr; using CollisionObjectRawPtr = fcl::CollisionObjectd*; using CollisionObjectConstPtr = std::shared_ptr; -enum CollisionFilterGroups +enum CollisionFilterGroups : std::int8_t { DefaultFilter = 1, StaticFilter = 2, diff --git a/tesseract_collision/fcl/src/fcl_collision_geometry_cache.cpp b/tesseract_collision/fcl/src/fcl_collision_geometry_cache.cpp index 34c0c6c2d1c..53c81d69d5a 100644 --- a/tesseract_collision/fcl/src/fcl_collision_geometry_cache.cpp +++ b/tesseract_collision/fcl/src/fcl_collision_geometry_cache.cpp @@ -32,7 +32,9 @@ namespace tesseract_collision::tesseract_collision_fcl { // Static member definitions +// NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables) std::map> FCLCollisionGeometryCache::cache_; +// NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables) std::mutex FCLCollisionGeometryCache::mutex_; void FCLCollisionGeometryCache::insert(const std::shared_ptr& key, diff --git a/tesseract_collision/test/collision_core_unit.cpp b/tesseract_collision/test/collision_core_unit.cpp index 2ec44bd4ff2..da6a71d7827 100644 --- a/tesseract_collision/test/collision_core_unit.cpp +++ b/tesseract_collision/test/collision_core_unit.cpp @@ -70,14 +70,14 @@ TEST(TesseractCoreUnit, isContactAllowedUnit) // NOLINT TEST(TesseractCoreUnit, scaleVerticesUnit) // NOLINT { tesseract_common::VectorVector3d base_vertices{}; - base_vertices.push_back(Eigen::Vector3d(0, 0, 0)); - base_vertices.push_back(Eigen::Vector3d(0, 0, 1)); - base_vertices.push_back(Eigen::Vector3d(0, 1, 1)); - base_vertices.push_back(Eigen::Vector3d(0, 1, 0)); - base_vertices.push_back(Eigen::Vector3d(1, 0, 0)); - base_vertices.push_back(Eigen::Vector3d(1, 0, 1)); - base_vertices.push_back(Eigen::Vector3d(1, 1, 1)); - base_vertices.push_back(Eigen::Vector3d(1, 1, 0)); + base_vertices.emplace_back(0, 0, 0); + base_vertices.emplace_back(0, 0, 1); + base_vertices.emplace_back(0, 1, 1); + base_vertices.emplace_back(0, 1, 0); + base_vertices.emplace_back(1, 0, 0); + base_vertices.emplace_back(1, 0, 1); + base_vertices.emplace_back(1, 1, 1); + base_vertices.emplace_back(1, 1, 0); // Test identity scale // NOLINTNEXTLINE(cppcoreguidelines-init-variables) diff --git a/tesseract_collision/test/contact_managers_factory_unit.cpp b/tesseract_collision/test/contact_managers_factory_unit.cpp index 6eca35d85f6..a6cb3991558 100644 --- a/tesseract_collision/test/contact_managers_factory_unit.cpp +++ b/tesseract_collision/test/contact_managers_factory_unit.cpp @@ -56,7 +56,7 @@ void runContactManagersFactoryTest(const tesseract_common::fs::path& config_path for (auto it = search_paths.begin(); it != search_paths.end(); ++it) { - EXPECT_TRUE(std::find(sp.begin(), sp.end(), it->as()) != sp.end()); + EXPECT_TRUE(sp.find(it->as()) != sp.end()); } } @@ -66,7 +66,7 @@ void runContactManagersFactoryTest(const tesseract_common::fs::path& config_path for (auto it = search_libraries.begin(); it != search_libraries.end(); ++it) { - EXPECT_TRUE(std::find(sl.begin(), sl.end(), it->as()) != sl.end()); + EXPECT_TRUE(sl.find(it->as()) != sl.end()); } } @@ -172,7 +172,7 @@ TEST(TesseractContactManagersFactoryUnit, LoadStringPluginTest) // NOLINT for (auto it = search_paths.begin(); it != search_paths.end(); ++it) { - EXPECT_TRUE(std::find(sp.begin(), sp.end(), it->as()) != sp.end()); + EXPECT_TRUE(sp.find(it->as()) != sp.end()); } } @@ -182,7 +182,7 @@ TEST(TesseractContactManagersFactoryUnit, LoadStringPluginTest) // NOLINT for (auto it = search_libraries.begin(); it != search_libraries.end(); ++it) { - EXPECT_TRUE(std::find(sl.begin(), sl.end(), it->as()) != sl.end()); + EXPECT_TRUE(sl.find(it->as()) != sl.end()); } } @@ -338,7 +338,7 @@ TEST(TesseractContactManagersFactoryUnit, LoadOnlyDiscretePluginTest) // NOLINT for (auto it = search_paths.begin(); it != search_paths.end(); ++it) { - EXPECT_TRUE(std::find(sp.begin(), sp.end(), it->as()) != sp.end()); + EXPECT_TRUE(sp.find(it->as()) != sp.end()); } } @@ -348,7 +348,7 @@ TEST(TesseractContactManagersFactoryUnit, LoadOnlyDiscretePluginTest) // NOLINT for (auto it = search_libraries.begin(); it != search_libraries.end(); ++it) { - EXPECT_TRUE(std::find(sl.begin(), sl.end(), it->as()) != sl.end()); + EXPECT_TRUE(sl.find(it->as()) != sl.end()); } } @@ -393,7 +393,7 @@ TEST(TesseractContactManagersFactoryUnit, LoadOnlyContinuousPluginTest) // NOLI for (auto it = search_paths.begin(); it != search_paths.end(); ++it) { - EXPECT_TRUE(std::find(sp.begin(), sp.end(), it->as()) != sp.end()); + EXPECT_TRUE(sp.find(it->as()) != sp.end()); } } @@ -403,7 +403,7 @@ TEST(TesseractContactManagersFactoryUnit, LoadOnlyContinuousPluginTest) // NOLI for (auto it = search_libraries.begin(); it != search_libraries.end(); ++it) { - EXPECT_TRUE(std::find(sl.begin(), sl.end(), it->as()) != sl.end()); + EXPECT_TRUE(sl.find(it->as()) != sl.end()); } } diff --git a/tesseract_collision/test_suite/include/tesseract_collision/test_suite/collision_large_dataset_unit.hpp b/tesseract_collision/test_suite/include/tesseract_collision/test_suite/collision_large_dataset_unit.hpp index fdbe4bf771a..56182bb7af1 100644 --- a/tesseract_collision/test_suite/include/tesseract_collision/test_suite/collision_large_dataset_unit.hpp +++ b/tesseract_collision/test_suite/include/tesseract_collision/test_suite/collision_large_dataset_unit.hpp @@ -94,7 +94,7 @@ inline void runTest(DiscreteContactManager& checker, bool use_convex_mesh = fals if (result_vector.size() != 300) for (const auto& result : result_vector) - std::cout << result.link_names[0] << "," << result.link_names[1] << "," << result.distance << std::endl; + std::cout << result.link_names[0] << "," << result.link_names[1] << "," << result.distance << "\n"; EXPECT_EQ(result_vector.size(), 300); } diff --git a/tesseract_collision/vhacd/src/convex_decomposition_vhacd.cpp b/tesseract_collision/vhacd/src/convex_decomposition_vhacd.cpp index 5f88ee91fb3..a4b0d5d59c5 100644 --- a/tesseract_collision/vhacd/src/convex_decomposition_vhacd.cpp +++ b/tesseract_collision/vhacd/src/convex_decomposition_vhacd.cpp @@ -27,7 +27,7 @@ class ProgressCallback : public VHACD::IVHACD::IUserCallback { std::cout << std::setfill(' ') << std::setw(3) << ceil(overallProgress) << "% " << "[ " << stage << " " << std::setfill(' ') << std::setw(3) << ceil(stageProgress) << "% ] " << operation - << std::endl; + << "\n"; } }; @@ -120,12 +120,12 @@ ConvexDecompositionVHACD::compute(const tesseract_common::VectorVector3d& vertic void VHACDParameters::print() const { std::stringstream msg; - msg << "+ Parameters" << std::endl; - msg << "\t Max number of convex hulls " << max_convex_hulls << std::endl; - msg << "\t Voxel resolution " << resolution << std::endl; - msg << "\t Volume error allowed as a percentage " << minimum_volume_percent_error_allowed << std::endl; - msg << "\t Maximum recursion depth " << max_recursion_depth << std::endl; - msg << "\t Shrinkwrap output to source mesh " << shrinkwrap << std::endl; + msg << "+ Parameters\n"; + msg << "\t Max number of convex hulls " << max_convex_hulls << "\n"; + msg << "\t Voxel resolution " << resolution << "\n"; + msg << "\t Volume error allowed as a percentage " << minimum_volume_percent_error_allowed << "\n"; + msg << "\t Maximum recursion depth " << max_recursion_depth << "\n"; + msg << "\t Shrinkwrap output to source mesh " << shrinkwrap << "\n"; msg << "\t Fill mode "; switch (fill_mode) { @@ -139,11 +139,11 @@ void VHACDParameters::print() const msg << "RAYCAST_FILL"; break; } - msg << std::endl; - msg << "\t Maximum number of vertices " << max_num_vertices_per_ch << std::endl; - msg << "\t Run asynchronously " << async_ACD << std::endl; - msg << "\t Minimum size of a voxel edge " << min_edge_length << std::endl; - msg << "\t Attempt to split planes along the best location " << find_best_plane << std::endl; + msg << "\n"; + msg << "\t Maximum number of vertices " << max_num_vertices_per_ch << "\n"; + msg << "\t Run asynchronously " << async_ACD << "\n"; + msg << "\t Minimum size of a voxel edge " << min_edge_length << "\n"; + msg << "\t Attempt to split planes along the best location " << find_best_plane << "\n"; std::cout << msg.str(); } diff --git a/tesseract_collision/vhacd/src/create_convex_decomposition.cpp b/tesseract_collision/vhacd/src/create_convex_decomposition.cpp index 823759fe32b..7d3ef1a9330 100644 --- a/tesseract_collision/vhacd/src/create_convex_decomposition.cpp +++ b/tesseract_collision/vhacd/src/create_convex_decomposition.cpp @@ -128,7 +128,7 @@ int main(int argc, char** argv) /** --help option */ if (vm.count("help") != 0U) { - std::cout << "Basic Command Line Parameter App" << std::endl << desc << std::endl; + std::cout << "Basic Command Line Parameter App\n" << desc << "\n"; return SUCCESS; } @@ -137,8 +137,8 @@ int main(int argc, char** argv) } catch (po::error& e) { - std::cerr << "ERROR: " << e.what() << std::endl << std::endl; - std::cerr << desc << std::endl; + std::cerr << "ERROR: " << e.what() << "\n\n"; + std::cerr << desc << "\n"; return ERROR_IN_COMMAND_LINE; } diff --git a/tesseract_common/include/tesseract_common/class_loader.hpp b/tesseract_common/include/tesseract_common/class_loader.hpp index f3a46fc0c48..9f4f220e2c6 100644 --- a/tesseract_common/include/tesseract_common/class_loader.hpp +++ b/tesseract_common/include/tesseract_common/class_loader.hpp @@ -37,8 +37,6 @@ TESSERACT_COMMON_IGNORE_WARNINGS_PUSH #include TESSERACT_COMMON_IGNORE_WARNINGS_POP -#include - namespace tesseract_common { template diff --git a/tesseract_common/include/tesseract_common/clone_cache.h b/tesseract_common/include/tesseract_common/clone_cache.h index 557755a7c83..e064f4a8f34 100644 --- a/tesseract_common/include/tesseract_common/clone_cache.h +++ b/tesseract_common/include/tesseract_common/clone_cache.h @@ -189,7 +189,7 @@ class CloneCache } } - const bool supports_update; + const bool supports_update; // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members) protected: void createClone() diff --git a/tesseract_common/include/tesseract_common/collision_margin_data.h b/tesseract_common/include/tesseract_common/collision_margin_data.h index f0c68992313..4cbf4aed5b0 100644 --- a/tesseract_common/include/tesseract_common/collision_margin_data.h +++ b/tesseract_common/include/tesseract_common/collision_margin_data.h @@ -47,7 +47,7 @@ class access; namespace tesseract_common { /** @brief Identifies how the provided contact margin data should be applied */ -enum class CollisionMarginOverrideType +enum class CollisionMarginOverrideType : std::uint8_t { /** @brief Do not apply contact margin data */ NONE, diff --git a/tesseract_common/include/tesseract_common/contact_allowed_validator.h b/tesseract_common/include/tesseract_common/contact_allowed_validator.h index 12cd93138dc..8761fca9daa 100644 --- a/tesseract_common/include/tesseract_common/contact_allowed_validator.h +++ b/tesseract_common/include/tesseract_common/contact_allowed_validator.h @@ -76,7 +76,7 @@ class ACMContactAllowedValidator : public ContactAllowedValidator }; /** @brief Identify how the two should be combined */ -enum class CombinedContactAllowedValidatorType +enum class CombinedContactAllowedValidatorType : std::uint8_t { /** @brief Combines the two ContactAllowedValidator with AND operator */ AND, diff --git a/tesseract_common/include/tesseract_common/fwd.h b/tesseract_common/include/tesseract_common/fwd.h index 3fbc89e1737..a26d81b09c2 100644 --- a/tesseract_common/include/tesseract_common/fwd.h +++ b/tesseract_common/include/tesseract_common/fwd.h @@ -27,6 +27,8 @@ #ifndef TESSERACT_COMMON_TESSERACT_COMMON_FWD_H #define TESSERACT_COMMON_TESSERACT_COMMON_FWD_H +#include + namespace tesseract_common { // types.h @@ -53,7 +55,7 @@ class ACMContactAllowedValidator; class CombinedContactAllowedValidator; // collision_margin_data.h -enum class CollisionMarginOverrideType; +enum class CollisionMarginOverrideType : std::uint8_t; class CollisionMarginData; // joint_state.h diff --git a/tesseract_common/include/tesseract_common/joint_state.h b/tesseract_common/include/tesseract_common/joint_state.h index 9b49981140e..ddcce0ce05b 100644 --- a/tesseract_common/include/tesseract_common/joint_state.h +++ b/tesseract_common/include/tesseract_common/joint_state.h @@ -228,7 +228,7 @@ class JointTrajectory /** @brief removes the last element */ void pop_back(); /** @brief swaps the contents */ - void swap(std::vector& other); + void swap(std::vector& other) noexcept; private: friend class boost::serialization::access; diff --git a/tesseract_common/include/tesseract_common/plugin_loader.hpp b/tesseract_common/include/tesseract_common/plugin_loader.hpp index 21e9bbddca7..13d631c7bae 100644 --- a/tesseract_common/include/tesseract_common/plugin_loader.hpp +++ b/tesseract_common/include/tesseract_common/plugin_loader.hpp @@ -33,7 +33,6 @@ TESSERACT_COMMON_IGNORE_WARNINGS_PUSH #include TESSERACT_COMMON_IGNORE_WARNINGS_POP -#include #include namespace tesseract_common @@ -147,16 +146,16 @@ std::shared_ptr PluginLoader::instantiate(const std::string& plugin_ std::stringstream msg; if (search_system_folders) - msg << std::endl << "Search Paths (Search System Folders: True):" << std::endl; + msg << "\nSearch Paths (Search System Folders: True):\n"; else - msg << std::endl << "Search Paths (Search System Folders: False):" << std::endl; + msg << "\nSearch Paths (Search System Folders: False):\n"; for (const auto& path : search_paths_local) - msg << " - " + path << std::endl; + msg << " - " + path << "\n"; - msg << "Search Libraries:" << std::endl; + msg << "Search Libraries:\n"; for (const auto& library : search_libraries) - msg << " - " + ClassLoader::decorate(library) << std::endl; + msg << " - " + ClassLoader::decorate(library) << "\n"; CONSOLE_BRIDGE_logError("Failed to instantiate plugin '%s', Details: %s", plugin_name.c_str(), msg.str().c_str()); diff --git a/tesseract_common/include/tesseract_common/serialization.h b/tesseract_common/include/tesseract_common/serialization.h index 242b61d9e96..b893fcd3454 100644 --- a/tesseract_common/include/tesseract_common/serialization.h +++ b/tesseract_common/include/tesseract_common/serialization.h @@ -197,7 +197,7 @@ struct Serialization } std::string data = ss.str(); - return std::vector(data.begin(), data.end()); + return { data.begin(), data.end() }; } template diff --git a/tesseract_common/include/tesseract_common/utils.h b/tesseract_common/include/tesseract_common/utils.h index 679ffb3337c..43785c29576 100644 --- a/tesseract_common/include/tesseract_common/utils.h +++ b/tesseract_common/include/tesseract_common/utils.h @@ -44,7 +44,7 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP namespace tinyxml2 { -class XMLElement; +class XMLElement; // NOLINT class XMLAttribute; } // namespace tinyxml2 diff --git a/tesseract_common/src/allowed_collision_matrix.cpp b/tesseract_common/src/allowed_collision_matrix.cpp index b1585b9f04e..f4343220423 100644 --- a/tesseract_common/src/allowed_collision_matrix.cpp +++ b/tesseract_common/src/allowed_collision_matrix.cpp @@ -122,7 +122,7 @@ void AllowedCollisionMatrix::serialize(Archive& ar, const unsigned int /*version std::ostream& operator<<(std::ostream& os, const AllowedCollisionMatrix& acm) { for (const auto& pair : acm.getAllAllowedCollisions()) - os << "link=" << pair.first.first << " link=" << pair.first.second << " reason=" << pair.second << std::endl; + os << "link=" << pair.first.first << " link=" << pair.first.second << " reason=" << pair.second << "\n"; return os; } } // namespace tesseract_common diff --git a/tesseract_common/src/collision_margin_data.cpp b/tesseract_common/src/collision_margin_data.cpp index 63b9d384c57..0aa0206509a 100644 --- a/tesseract_common/src/collision_margin_data.cpp +++ b/tesseract_common/src/collision_margin_data.cpp @@ -157,10 +157,7 @@ void CollisionMarginData::updateMaxCollisionMargin() { max_collision_margin_ = default_collision_margin_; for (const auto& p : lookup_table_) - { - if (p.second > max_collision_margin_) - max_collision_margin_ = p.second; - } + max_collision_margin_ = std::max(p.second, max_collision_margin_); } bool CollisionMarginData::operator==(const CollisionMarginData& rhs) const diff --git a/tesseract_common/src/joint_state.cpp b/tesseract_common/src/joint_state.cpp index 6cc6b7812ec..c3586e25fa3 100644 --- a/tesseract_common/src/joint_state.cpp +++ b/tesseract_common/src/joint_state.cpp @@ -134,7 +134,10 @@ JointTrajectory::const_reference JointTrajectory::operator[](size_type pos) cons /////////////// void JointTrajectory::clear() { states.clear(); } JointTrajectory::iterator JointTrajectory::insert(const_iterator p, const value_type& x) { return states.insert(p, x); } -JointTrajectory::iterator JointTrajectory::insert(const_iterator p, value_type&& x) { return states.insert(p, x); } +JointTrajectory::iterator JointTrajectory::insert(const_iterator p, value_type&& x) +{ + return states.insert(p, std::move(x)); +} JointTrajectory::iterator JointTrajectory::insert(const_iterator p, std::initializer_list l) { return states.insert(p, l); @@ -168,7 +171,7 @@ void JointTrajectory::emplace_back(Args&&... args) #endif void JointTrajectory::pop_back() { states.pop_back(); } -void JointTrajectory::swap(std::vector& other) { states.swap(other); } +void JointTrajectory::swap(std::vector& other) noexcept { states.swap(other); } // LCOV_EXCL_STOP diff --git a/tesseract_common/src/resource_locator.cpp b/tesseract_common/src/resource_locator.cpp index 39c7f3817e4..e37eb59d4b3 100644 --- a/tesseract_common/src/resource_locator.cpp +++ b/tesseract_common/src/resource_locator.cpp @@ -332,7 +332,7 @@ std::shared_ptr BytesResource::getResourceContentStream() const { std::shared_ptr o = std::make_shared(); o->write((const char*)&bytes_.at(0), static_cast(bytes_.size())); // NOLINT - o->seekg(0, o->beg); + o->seekg(0, std::stringstream::beg); return o; } diff --git a/tesseract_common/src/utils.cpp b/tesseract_common/src/utils.cpp index b68e832ebda..a4cfb7aac7e 100644 --- a/tesseract_common/src/utils.cpp +++ b/tesseract_common/src/utils.cpp @@ -183,10 +183,10 @@ Eigen::VectorXd calcJacobianTransformErrorDiff(const Eigen::Isometry3d& target, Eigen::VectorXd perturbed_err; if (perturbed_pose_rotation_err.second > M_PI_2 && pose_rotation_err.second < -M_PI_2) perturbed_err = concat(perturbed_pose_err.translation(), - perturbed_pose_rotation_err.first * (perturbed_pose_rotation_err.second - 2 * M_PI)); + perturbed_pose_rotation_err.first * (perturbed_pose_rotation_err.second - (2 * M_PI))); else if (perturbed_pose_rotation_err.second < -M_PI_2 && pose_rotation_err.second > M_PI_2) perturbed_err = concat(perturbed_pose_err.translation(), - perturbed_pose_rotation_err.first * (perturbed_pose_rotation_err.second + 2 * M_PI)); + perturbed_pose_rotation_err.first * (perturbed_pose_rotation_err.second + (2 * M_PI))); else perturbed_err = concat(perturbed_pose_err.translation(), perturbed_pose_rotation_err.first * perturbed_pose_rotation_err.second); @@ -217,10 +217,10 @@ Eigen::VectorXd calcJacobianTransformErrorDiff(const Eigen::Isometry3d& target, Eigen::VectorXd perturbed_err; if (perturbed_pose_rotation_err.second > M_PI_2 && pose_rotation_err.second < -M_PI_2) perturbed_err = concat(perturbed_pose_err.translation(), - perturbed_pose_rotation_err.first * (perturbed_pose_rotation_err.second - 2 * M_PI)); + perturbed_pose_rotation_err.first * (perturbed_pose_rotation_err.second - (2 * M_PI))); else if (perturbed_pose_rotation_err.second < -M_PI_2 && pose_rotation_err.second > M_PI_2) perturbed_err = concat(perturbed_pose_err.translation(), - perturbed_pose_rotation_err.first * (perturbed_pose_rotation_err.second + 2 * M_PI)); + perturbed_pose_rotation_err.first * (perturbed_pose_rotation_err.second + (2 * M_PI))); else perturbed_err = concat(perturbed_pose_err.translation(), perturbed_pose_rotation_err.first * perturbed_pose_rotation_err.second); @@ -245,7 +245,7 @@ Eigen::Vector4d computeRandomColor() void printNestedException(const std::exception& e, int level) // NOLINT(misc-no-recursion) { - std::cerr << std::string(static_cast(2 * level), ' ') << "exception: " << e.what() << std::endl; + std::cerr << std::string(static_cast(2 * level), ' ') << "exception: " << e.what() << "\n"; try { my_rethrow_if_nested(e); @@ -254,7 +254,7 @@ void printNestedException(const std::exception& e, int level) // NOLINT(misc-no { printNestedException(e, level + 1); } - catch (...) + catch (...) // NOLINT { } } @@ -274,7 +274,7 @@ bool isNumeric(const std::string& s) double out{ 0 }; ss >> out; - return !(ss.fail() || !ss.eof()); + return !ss.fail() && ss.eof(); } bool isNumeric(const std::vector& sv) diff --git a/tesseract_common/test/plugin_loader_unit.cpp b/tesseract_common/test/plugin_loader_unit.cpp index e6facbe084c..df6af4c9c38 100644 --- a/tesseract_common/test/plugin_loader_unit.cpp +++ b/tesseract_common/test/plugin_loader_unit.cpp @@ -58,7 +58,7 @@ TEST(TesseractClassLoaderUnit, LoadTestPlugin) // NOLINT const std::string symbol_name = "plugin"; { - std::vector sections = ClassLoader::getAvailableSections(lib_name, lib_dir); + std::vector sections = ClassLoader::getAvailableSections(lib_name, lib_dir); // NOLINT EXPECT_EQ(sections.size(), 1); EXPECT_EQ(sections.at(0), "TestBase"); diff --git a/tesseract_common/test/tesseract_common_unit.cpp b/tesseract_common/test/tesseract_common_unit.cpp index 22b6fab9e48..269118feeed 100644 --- a/tesseract_common/test/tesseract_common_unit.cpp +++ b/tesseract_common/test/tesseract_common_unit.cpp @@ -39,7 +39,6 @@ class TestResourceLocator : public tesseract_common::ResourceLocator if (pos == std::string::npos) return nullptr; - std::string package = mod_url.substr(0, pos); mod_url.erase(0, pos); tesseract_common::fs::path file_path(__FILE__); @@ -263,10 +262,9 @@ TEST(TesseractCommonUnit, sfinaeHasMemberFunctionSignature) // NOLINT TEST(TesseractCommonUnit, bytesResource) // NOLINT { std::vector data; + data.reserve(8); for (uint8_t i = 0; i < 8; i++) - { data.push_back(i); - } std::shared_ptr bytes_resource = std::make_shared("package://test_package/data.bin", data); @@ -466,7 +464,7 @@ template void runAnyPolyUnorderedMapIntegralTest(T value, const std::string& type_str) { std::unordered_map data; - data["test"] = value; + data["test"] = std::move(value); tesseract_common::AnyPoly any_type{ data }; EXPECT_TRUE(any_type.getType() == std::type_index(typeid(std::unordered_map))); bool check = any_type.as>() == data; diff --git a/tesseract_environment/include/tesseract_environment/commands/add_link_command.h b/tesseract_environment/include/tesseract_environment/commands/add_link_command.h index ea8ca5e4c55..3f4ee56bc60 100644 --- a/tesseract_environment/include/tesseract_environment/commands/add_link_command.h +++ b/tesseract_environment/include/tesseract_environment/commands/add_link_command.h @@ -112,7 +112,6 @@ class AddLinkCommand : public Command }; } // namespace tesseract_environment -#include BOOST_CLASS_EXPORT_KEY(tesseract_environment::AddLinkCommand) #endif // TESSERACT_ENVIRONMENT_ADD_COMMAND_H diff --git a/tesseract_environment/include/tesseract_environment/events.h b/tesseract_environment/include/tesseract_environment/events.h index 9474275a01a..a5877e14030 100644 --- a/tesseract_environment/include/tesseract_environment/events.h +++ b/tesseract_environment/include/tesseract_environment/events.h @@ -54,7 +54,7 @@ struct Event Event(Event&&) = default; Event& operator=(Event&&) = delete; - const Events type; + const Events type; // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members) }; /** @@ -65,7 +65,8 @@ struct CommandAppliedEvent : public Event { CommandAppliedEvent(const std::vector>& commands, int revision); - const std::vector>& commands; + const std::vector>& + commands; // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members) int revision; }; @@ -77,7 +78,7 @@ struct SceneStateChangedEvent : public Event { SceneStateChangedEvent(const tesseract_scene_graph::SceneState& state); - const tesseract_scene_graph::SceneState& state; + const tesseract_scene_graph::SceneState& state; // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members) }; } // namespace tesseract_environment diff --git a/tesseract_environment/src/commands/change_joint_origin_command.cpp b/tesseract_environment/src/commands/change_joint_origin_command.cpp index 106a8876870..d88c055cfd3 100644 --- a/tesseract_environment/src/commands/change_joint_origin_command.cpp +++ b/tesseract_environment/src/commands/change_joint_origin_command.cpp @@ -39,6 +39,7 @@ namespace tesseract_environment { ChangeJointOriginCommand::ChangeJointOriginCommand() : Command(CommandType::CHANGE_JOINT_ORIGIN){}; +// NOLINTNEXTLINE(modernize-pass-by-value) ChangeJointOriginCommand::ChangeJointOriginCommand(std::string joint_name, const Eigen::Isometry3d& origin) : Command(CommandType::CHANGE_JOINT_ORIGIN), joint_name_(std::move(joint_name)), origin_(origin) { diff --git a/tesseract_environment/src/commands/change_link_origin_command.cpp b/tesseract_environment/src/commands/change_link_origin_command.cpp index 4215ce574ee..bfb7ea4178b 100644 --- a/tesseract_environment/src/commands/change_link_origin_command.cpp +++ b/tesseract_environment/src/commands/change_link_origin_command.cpp @@ -42,6 +42,7 @@ namespace tesseract_environment { ChangeLinkOriginCommand::ChangeLinkOriginCommand() : Command(CommandType::CHANGE_LINK_ORIGIN) {} +// NOLINTNEXTLINE(modernize-pass-by-value) ChangeLinkOriginCommand::ChangeLinkOriginCommand(std::string link_name, const Eigen::Isometry3d& origin) : Command(CommandType::CHANGE_LINK_ORIGIN), link_name_(std::move(link_name)), origin_(origin) { diff --git a/tesseract_environment/src/environment.cpp b/tesseract_environment/src/environment.cpp index b252d867049..b82f66a8fcb 100644 --- a/tesseract_environment/src/environment.cpp +++ b/tesseract_environment/src/environment.cpp @@ -1359,7 +1359,7 @@ bool Environment::Implementation::applyCommandsHelper(const std::vectorgetLink() && !cmd->getJoint())); + assert(!(!cmd->getLink() && !cmd->getJoint())); // NOLINT assert(!((cmd->getLink() != nullptr) && (cmd->getJoint() != nullptr) && (cmd->getJoint()->child_link_name != cmd->getLink()->getName()))); diff --git a/tesseract_environment/src/utils.cpp b/tesseract_environment/src/utils.cpp index a17f77bc7b9..e9bbf1cc144 100644 --- a/tesseract_environment/src/utils.cpp +++ b/tesseract_environment/src/utils.cpp @@ -138,13 +138,15 @@ void printContinuousDebugInfo(const std::vector& joint_names, ss << "Continuous collision detected at step: " << step_idx << " of " << step_size; if (sub_step_idx >= 0) ss << " substep: " << sub_step_idx; - ss << std::endl; + ss << "\n"; ss << " Names:"; for (const auto& name : joint_names) ss << " " << name; - ss << std::endl << " State0: " << swp0 << std::endl << " State1: " << swp1 << std::endl; + ss << "\n" + << " State0: " << swp0 << "\n" + << " State1: " << swp1 << "\n"; CONSOLE_BRIDGE_logDebug(ss.str().c_str()); } @@ -159,13 +161,14 @@ void printDiscreteDebugInfo(const std::vector& joint_names, ss << "Discrete collision detected at step: " << step_idx << " of " << step_size; if (sub_step_idx >= 0) ss << " substep: " << sub_step_idx; - ss << std::endl; + ss << "\n"; ss << " Names:"; for (const auto& name : joint_names) ss << " " << name; - ss << std::endl << " State: " << swp << std::endl; + ss << "\n" + << " State: " << swp << "\n"; CONSOLE_BRIDGE_logDebug(ss.str().c_str()); } @@ -341,7 +344,7 @@ bool checkTrajectory(std::vector& contact if (config.check_program_mode == tesseract_collision::CollisionCheckProgramType::ALL_EXCEPT_START || config.check_program_mode == tesseract_collision::CollisionCheckProgramType::INTERMEDIATE_ONLY) { - contacts.emplace_back(tesseract_collision::ContactResultMap{}); + contacts.emplace_back(); continue; } } @@ -397,7 +400,7 @@ bool checkTrajectory(std::vector& contact if (config.check_program_mode == tesseract_collision::CollisionCheckProgramType::ALL_EXCEPT_START || config.check_program_mode == tesseract_collision::CollisionCheckProgramType::INTERMEDIATE_ONLY) { - contacts.emplace_back(tesseract_collision::ContactResultMap{}); + contacts.emplace_back(); ++start_idx; } @@ -750,7 +753,7 @@ bool checkTrajectory(std::vector& contact if (config.check_program_mode == tesseract_collision::CollisionCheckProgramType::ALL_EXCEPT_START || config.check_program_mode == tesseract_collision::CollisionCheckProgramType::INTERMEDIATE_ONLY) { - contacts.emplace_back(tesseract_collision::ContactResultMap{}); + contacts.emplace_back(); continue; } } @@ -827,7 +830,7 @@ bool checkTrajectory(std::vector& contact if (config.check_program_mode == tesseract_collision::CollisionCheckProgramType::ALL_EXCEPT_START || config.check_program_mode == tesseract_collision::CollisionCheckProgramType::INTERMEDIATE_ONLY) { - contacts.emplace_back(tesseract_collision::ContactResultMap{}); + contacts.emplace_back(); ++start_idx; } diff --git a/tesseract_geometry/include/tesseract_geometry/fwd.h b/tesseract_geometry/include/tesseract_geometry/fwd.h index 22f4d224dcf..c9f441e8e1f 100644 --- a/tesseract_geometry/include/tesseract_geometry/fwd.h +++ b/tesseract_geometry/include/tesseract_geometry/fwd.h @@ -26,9 +26,11 @@ #ifndef TESSERACT_GEOMETRY_TESSERACT_GEOMETRY_FWD_H #define TESSERACT_GEOMETRY_TESSERACT_GEOMETRY_FWD_H +#include + namespace tesseract_geometry { -enum class GeometryType; +enum class GeometryType : std::uint8_t; class Geometry; class Box; class Capsule; @@ -39,7 +41,7 @@ class MeshMaterial; class MeshTexture; class Mesh; class Octree; -enum class OctreeSubType; +enum class OctreeSubType : std::uint8_t; class Plane; class PolygonMesh; class SDFMesh; diff --git a/tesseract_geometry/include/tesseract_geometry/geometry.h b/tesseract_geometry/include/tesseract_geometry/geometry.h index cab889f7d5a..cd395f7c0cf 100644 --- a/tesseract_geometry/include/tesseract_geometry/geometry.h +++ b/tesseract_geometry/include/tesseract_geometry/geometry.h @@ -33,6 +33,7 @@ TESSERACT_COMMON_IGNORE_WARNINGS_PUSH #include #include #include +#include TESSERACT_COMMON_IGNORE_WARNINGS_POP namespace boost::serialization @@ -42,7 +43,7 @@ class access; namespace tesseract_geometry { -enum class GeometryType +enum class GeometryType : std::uint8_t { UNINITIALIZED, SPHERE, diff --git a/tesseract_geometry/include/tesseract_geometry/impl/capsule.h b/tesseract_geometry/include/tesseract_geometry/impl/capsule.h index 2c974dcbfe6..7d00900e49a 100644 --- a/tesseract_geometry/include/tesseract_geometry/impl/capsule.h +++ b/tesseract_geometry/include/tesseract_geometry/impl/capsule.h @@ -47,7 +47,7 @@ class Capsule : public Geometry using Ptr = std::shared_ptr; using ConstPtr = std::shared_ptr; - Capsule(double r, double l); + Capsule(double radius, double length); Capsule() = default; ~Capsule() override = default; diff --git a/tesseract_geometry/include/tesseract_geometry/impl/cone.h b/tesseract_geometry/include/tesseract_geometry/impl/cone.h index f4bfb0ff505..c9b7edc9ed9 100644 --- a/tesseract_geometry/include/tesseract_geometry/impl/cone.h +++ b/tesseract_geometry/include/tesseract_geometry/impl/cone.h @@ -47,7 +47,7 @@ class Cone : public Geometry using Ptr = std::shared_ptr; using ConstPtr = std::shared_ptr; - Cone(double r, double l); + Cone(double radius, double length); Cone() = default; ~Cone() override = default; diff --git a/tesseract_geometry/include/tesseract_geometry/impl/convex_mesh.h b/tesseract_geometry/include/tesseract_geometry/impl/convex_mesh.h index 92c49ee5f61..c124f9a0ebd 100644 --- a/tesseract_geometry/include/tesseract_geometry/impl/convex_mesh.h +++ b/tesseract_geometry/include/tesseract_geometry/impl/convex_mesh.h @@ -52,7 +52,7 @@ class ConvexMesh : public PolygonMesh using Ptr = std::shared_ptr; using ConstPtr = std::shared_ptr; - enum CreationMethod + enum CreationMethod : std::uint8_t { DEFAULT, MESH, diff --git a/tesseract_geometry/include/tesseract_geometry/impl/cylinder.h b/tesseract_geometry/include/tesseract_geometry/impl/cylinder.h index 363201593c7..daeb5666e52 100644 --- a/tesseract_geometry/include/tesseract_geometry/impl/cylinder.h +++ b/tesseract_geometry/include/tesseract_geometry/impl/cylinder.h @@ -47,7 +47,7 @@ class Cylinder : public Geometry using Ptr = std::shared_ptr; using ConstPtr = std::shared_ptr; - Cylinder(double r, double l); + Cylinder(double radius, double length); Cylinder() = default; ~Cylinder() override = default; diff --git a/tesseract_geometry/include/tesseract_geometry/impl/octree.h b/tesseract_geometry/include/tesseract_geometry/impl/octree.h index 93fe14a6fc1..bff87e75de8 100644 --- a/tesseract_geometry/include/tesseract_geometry/impl/octree.h +++ b/tesseract_geometry/include/tesseract_geometry/impl/octree.h @@ -48,7 +48,7 @@ class OcTreeNode; namespace tesseract_geometry { -enum class OctreeSubType +enum class OctreeSubType : std::uint8_t { BOX, SPHERE_INSIDE, diff --git a/tesseract_geometry/include/tesseract_geometry/mesh_parser.h b/tesseract_geometry/include/tesseract_geometry/mesh_parser.h index 652b655628d..11a1c123ce2 100644 --- a/tesseract_geometry/include/tesseract_geometry/mesh_parser.h +++ b/tesseract_geometry/include/tesseract_geometry/mesh_parser.h @@ -99,9 +99,9 @@ std::vector> extractMeshData(const aiScene* scene, for (unsigned int i = 0; i < a->mNumVertices; ++i) { aiVector3D v = transform * a->mVertices[i]; - vertices->push_back(Eigen::Vector3d(static_cast(v.x) * scale(0), - static_cast(v.y) * scale(1), - static_cast(v.z) * scale(2))); + vertices->emplace_back(static_cast(v.x) * scale(0), + static_cast(v.y) * scale(1), + static_cast(v.z) * scale(2)); } long triangle_count = 0; @@ -133,9 +133,9 @@ std::vector> extractMeshData(const aiScene* scene, for (unsigned int i = 0; i < a->mNumVertices; ++i) { aiVector3D v = transform * a->mNormals[i]; - vertex_normals->push_back(Eigen::Vector3d(static_cast(v.x) * scale(0), - static_cast(v.y) * scale(1), - static_cast(v.z) * scale(2))); + vertex_normals->emplace_back(static_cast(v.x) * scale(0), + static_cast(v.y) * scale(1), + static_cast(v.z) * scale(2)); } } @@ -146,8 +146,8 @@ std::vector> extractMeshData(const aiScene* scene, for (unsigned int i = 0; i < a->mNumVertices; ++i) { aiColor4D v = a->mColors[0][i]; - vertex_colors->push_back(Eigen::Vector4d( - static_cast(v.r), static_cast(v.g), static_cast(v.b), static_cast(v.a))); + vertex_colors->emplace_back( + static_cast(v.r), static_cast(v.g), static_cast(v.b), static_cast(v.a)); } } @@ -252,7 +252,7 @@ std::vector> extractMeshData(const aiScene* scene, for (unsigned int j = 0; j < a->mNumVertices; ++j) { aiVector3D v = tex_coords[j]; - uvs.push_back(Eigen::Vector2d(static_cast(v.x), static_cast(v.y))); + uvs.emplace_back(static_cast(v.x), static_cast(v.y)); } auto tex = std::make_shared( texture_image, std::make_shared(std::move(uvs))); diff --git a/tesseract_geometry/src/geometries/capsule.cpp b/tesseract_geometry/src/geometries/capsule.cpp index f5d250a9b35..08828c7b8e9 100644 --- a/tesseract_geometry/src/geometries/capsule.cpp +++ b/tesseract_geometry/src/geometries/capsule.cpp @@ -34,7 +34,7 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP namespace tesseract_geometry { -Capsule::Capsule(double r, double l) : Geometry(GeometryType::CAPSULE), r_(r), l_(l) {} +Capsule::Capsule(double radius, double length) : Geometry(GeometryType::CAPSULE), r_(radius), l_(length) {} double Capsule::getRadius() const { return r_; } double Capsule::getLength() const { return l_; } diff --git a/tesseract_geometry/src/geometries/cone.cpp b/tesseract_geometry/src/geometries/cone.cpp index f73bf65c9df..1b8c394b83b 100644 --- a/tesseract_geometry/src/geometries/cone.cpp +++ b/tesseract_geometry/src/geometries/cone.cpp @@ -34,7 +34,7 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP namespace tesseract_geometry { -Cone::Cone(double r, double l) : Geometry(GeometryType::CONE), r_(r), l_(l) {} +Cone::Cone(double radius, double length) : Geometry(GeometryType::CONE), r_(radius), l_(length) {} double Cone::getRadius() const { return r_; } double Cone::getLength() const { return l_; } diff --git a/tesseract_geometry/src/geometries/cylinder.cpp b/tesseract_geometry/src/geometries/cylinder.cpp index 210c5468cb6..8f636e5d06c 100644 --- a/tesseract_geometry/src/geometries/cylinder.cpp +++ b/tesseract_geometry/src/geometries/cylinder.cpp @@ -34,7 +34,7 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP namespace tesseract_geometry { -Cylinder::Cylinder(double r, double l) : Geometry(GeometryType::CYLINDER), r_(r), l_(l) {} +Cylinder::Cylinder(double radius, double length) : Geometry(GeometryType::CYLINDER), r_(radius), l_(length) {} double Cylinder::getRadius() const { return r_; } double Cylinder::getLength() const { return l_; } diff --git a/tesseract_geometry/src/geometry.cpp b/tesseract_geometry/src/geometry.cpp index 63cbf9b8663..31492c820c7 100644 --- a/tesseract_geometry/src/geometry.cpp +++ b/tesseract_geometry/src/geometry.cpp @@ -55,4 +55,3 @@ void Geometry::serialize(Archive& ar, const unsigned int /*version*/) } // namespace tesseract_geometry TESSERACT_SERIALIZE_ARCHIVES_INSTANTIATE(tesseract_geometry::Geometry) -#include diff --git a/tesseract_kinematics/core/include/tesseract_kinematics/core/utils.h b/tesseract_kinematics/core/include/tesseract_kinematics/core/utils.h index e6b012e5f74..5ec54ec9b03 100644 --- a/tesseract_kinematics/core/include/tesseract_kinematics/core/utils.h +++ b/tesseract_kinematics/core/include/tesseract_kinematics/core/utils.h @@ -190,8 +190,7 @@ inline void getRedundantSolutionsHelper(std::vector>& redunda if (std::isinf(limits(*current_index, 0))) { std::stringstream ss; - ss << "Lower limit of joint " << *current_index << " is infinite; no redundant solutions will be generated" - << std::endl; + ss << "Lower limit of joint " << *current_index << " is infinite; no redundant solutions will be generated\n"; CONSOLE_BRIDGE_logWarn(ss.str().c_str()); } else @@ -221,8 +220,7 @@ inline void getRedundantSolutionsHelper(std::vector>& redunda if (std::isinf(limits(*current_index, 1))) { std::stringstream ss; - ss << "Upper limit of joint " << *current_index << " is infinite; no redundant solutions will be generated" - << std::endl; + ss << "Upper limit of joint " << *current_index << " is infinite; no redundant solutions will be generated\n"; CONSOLE_BRIDGE_logWarn(ss.str().c_str()); } else diff --git a/tesseract_kinematics/core/src/kinematic_group.cpp b/tesseract_kinematics/core/src/kinematic_group.cpp index f67786457c2..c74ccf1b8b0 100644 --- a/tesseract_kinematics/core/src/kinematic_group.cpp +++ b/tesseract_kinematics/core/src/kinematic_group.cpp @@ -38,6 +38,7 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP namespace tesseract_kinematics { +// NOLINTNEXTLINE(modernize-pass-by-value) KinGroupIKInput::KinGroupIKInput(const Eigen::Isometry3d& p, std::string wf, std::string tl) : pose(p), working_frame(std::move(wf)), tip_link_name(std::move(tl)) { diff --git a/tesseract_kinematics/core/src/kinematics_plugin_factory.cpp b/tesseract_kinematics/core/src/kinematics_plugin_factory.cpp index 7a26455fa41..e7c5b9c9202 100644 --- a/tesseract_kinematics/core/src/kinematics_plugin_factory.cpp +++ b/tesseract_kinematics/core/src/kinematics_plugin_factory.cpp @@ -33,7 +33,7 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP #include #include #include -#include +#include #include #include #include diff --git a/tesseract_kinematics/core/src/utils.cpp b/tesseract_kinematics/core/src/utils.cpp index 7c423f9c6b4..79b1e533084 100644 --- a/tesseract_kinematics/core/src/utils.cpp +++ b/tesseract_kinematics/core/src/utils.cpp @@ -197,7 +197,7 @@ Manipulability calcManipulability(const Eigen::Ref& jacob data.eigen_values = sm.eigenvalues().real(); // Set eigenvalues near zero to zero. This also implies zero volume - for (Eigen::Index i = 0; i < data.eigen_values.size(); ++i) + for (Eigen::Index i = 0; i < data.eigen_values.size(); ++i) // NOLINT(modernize-loop-convert) { if (tesseract_common::almostEqualRelativeAndAbs(data.eigen_values[i], 0)) data.eigen_values[i] = +0; diff --git a/tesseract_kinematics/core/src/validate.cpp b/tesseract_kinematics/core/src/validate.cpp index d0e951a19d4..188e1cad5d2 100644 --- a/tesseract_kinematics/core/src/validate.cpp +++ b/tesseract_kinematics/core/src/validate.cpp @@ -132,29 +132,30 @@ bool checkKinematics(const KinematicGroup& manip, double tol) failed_data.size(), angular_max); std::stringstream msg; - msg << std::endl; - msg << "*****************************" << std::endl; - msg << "******** Failed Data ********" << std::endl; - msg << "*****************************" << std::endl; + msg << "\n"; + msg << "*****************************\n"; + msg << "******** Failed Data ********\n"; + msg << "*****************************\n"; std::string header = "Trans. Dist. (m), tol, Angle Dist. (rad), tol"; for (const auto& jn : manip.getJointNames()) header += ", " + jn; - msg << header << std::endl; + msg << header << "\n"; for (const auto& d : failed_data) { for (const auto& val : d) msg << val << ", "; - msg << std::endl; + msg << "\n"; } - msg << "*****************************" << std::endl; - msg << "******** Passed Data ********" << std::endl; - msg << "*****************************" << std::endl; + msg << "*****************************\n"; + msg << "******** Passed Data ********\n"; + msg << "*****************************\n"; if (passed_data.empty()) { - msg << "No Data!" << std::endl; + msg << "No Data!" + << "\n"; } else { @@ -162,7 +163,7 @@ bool checkKinematics(const KinematicGroup& manip, double tol) { for (const auto& val : d) msg << val << ", "; - msg << std::endl; + msg << "\n"; } } diff --git a/tesseract_kinematics/opw/src/opw_inv_kin.cpp b/tesseract_kinematics/opw/src/opw_inv_kin.cpp index 843b73d994a..698c17fbaac 100644 --- a/tesseract_kinematics/opw/src/opw_inv_kin.cpp +++ b/tesseract_kinematics/opw/src/opw_inv_kin.cpp @@ -81,7 +81,7 @@ IKSolutions OPWInvKin::calcInvKin(const tesseract_common::TransformMap& tip_link for (auto& sol : sols) { if (opw_kinematics::isValid(sol)) - solution_set.push_back(Eigen::Map(sol.data(), static_cast(sol.size()))); + solution_set.emplace_back(Eigen::Map(sol.data(), static_cast(sol.size()))); } return solution_set; diff --git a/tesseract_kinematics/ur/src/ur_inv_kin.cpp b/tesseract_kinematics/ur/src/ur_inv_kin.cpp index 5332ee02736..22093d6de9e 100644 --- a/tesseract_kinematics/ur/src/ur_inv_kin.cpp +++ b/tesseract_kinematics/ur/src/ur_inv_kin.cpp @@ -278,7 +278,7 @@ IKSolutions URInvKin::calcInvKin(const tesseract_common::TransformMap& tip_link_ harmonizeTowardZero(eigen_sol, REDUNDANT_CAPABLE_JOINTS); // Modifies 'sol' in place // Add solution - solution_set.push_back(eigen_sol); + solution_set.emplace_back(eigen_sol); } return solution_set; diff --git a/tesseract_scene_graph/include/tesseract_scene_graph/fwd.h b/tesseract_scene_graph/include/tesseract_scene_graph/fwd.h index c22a38b22de..284e71b5bcc 100644 --- a/tesseract_scene_graph/include/tesseract_scene_graph/fwd.h +++ b/tesseract_scene_graph/include/tesseract_scene_graph/fwd.h @@ -27,6 +27,8 @@ #ifndef TESSERACT_SCENE_GRAPH_FWD_H #define TESSERACT_SCENE_GRAPH_FWD_H +#include + namespace tesseract_scene_graph { // joint.h @@ -35,7 +37,7 @@ class JointLimits; class JointSafety; class JointCalibration; class JointMimic; -enum class JointType; +enum class JointType : std::uint8_t; class Joint; // link.h diff --git a/tesseract_scene_graph/include/tesseract_scene_graph/graph.h b/tesseract_scene_graph/include/tesseract_scene_graph/graph.h index d03363c37eb..6d5a2cfe74f 100644 --- a/tesseract_scene_graph/include/tesseract_scene_graph/graph.h +++ b/tesseract_scene_graph/include/tesseract_scene_graph/graph.h @@ -48,23 +48,23 @@ class access; /* definition of basic boost::graph properties */ namespace boost { -enum vertex_link_t +enum vertex_link_t : std::uint8_t { vertex_link }; -enum vertex_link_visible_t +enum vertex_link_visible_t : std::uint8_t { vertex_link_visible }; -enum vertex_link_collision_enabled_t +enum vertex_link_collision_enabled_t : std::uint8_t { vertex_link_collision_enabled }; -enum edge_joint_t +enum edge_joint_t : std::uint8_t { edge_joint }; -enum graph_root_t +enum graph_root_t : std::uint8_t { graph_root }; diff --git a/tesseract_scene_graph/include/tesseract_scene_graph/joint.h b/tesseract_scene_graph/include/tesseract_scene_graph/joint.h index 2b515d2a38f..1540172858a 100644 --- a/tesseract_scene_graph/include/tesseract_scene_graph/joint.h +++ b/tesseract_scene_graph/include/tesseract_scene_graph/joint.h @@ -251,7 +251,7 @@ class JointMimic std::ostream& operator<<(std::ostream& os, const JointMimic& mimic); -enum class JointType +enum class JointType : std::uint8_t { UNKNOWN, REVOLUTE, diff --git a/tesseract_scene_graph/src/graph.cpp b/tesseract_scene_graph/src/graph.cpp index bd87dbeec69..94a0c62978c 100644 --- a/tesseract_scene_graph/src/graph.cpp +++ b/tesseract_scene_graph/src/graph.cpp @@ -66,7 +66,7 @@ struct cycle_detector : public boost::dfs_visitor<> } protected: - bool& ascyclic_; + bool& ascyclic_; // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members) }; struct tree_detector : public boost::dfs_visitor<> @@ -109,7 +109,7 @@ struct tree_detector : public boost::dfs_visitor<> } protected: - bool& tree_; + bool& tree_; // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members) bool found_root_{ false }; }; @@ -124,7 +124,7 @@ struct children_detector : public boost::default_bfs_visitor } protected: - std::vector& children_; + std::vector& children_; // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members) }; struct adjacency_detector : public boost::default_bfs_visitor @@ -159,10 +159,12 @@ struct adjacency_detector : public boost::default_bfs_visitor } protected: + // NOLINTNEXTLINE(cppcoreguidelines-avoid-const-or-ref-data-members) std::unordered_map& adjacency_map_; + // NOLINTNEXTLINE(cppcoreguidelines-avoid-const-or-ref-data-members) std::map& color_map_; - const std::string& base_link_name_; - const std::vector& terminate_on_links_; + const std::string& base_link_name_; // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members) + const std::vector& terminate_on_links_; // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members) }; using UGraph = @@ -190,7 +192,7 @@ SceneGraph::SceneGraph(const std::string& name) : acm_(std::make_shared(other)) + : Graph(other) // Graph does not have a move constructor , link_map_(std::move(other.link_map_)) , joint_map_(std::move(other.joint_map_)) , acm_(std::move(other.acm_)) @@ -200,7 +202,7 @@ SceneGraph::SceneGraph(SceneGraph&& other) noexcept SceneGraph& SceneGraph::operator=(SceneGraph&& other) noexcept { - Graph::operator=(std::forward(other)); + Graph::operator=(other); // Graph does not have move assignment operator link_map_ = std::move(other.link_map_); joint_map_ = std::move(other.joint_map_); @@ -1342,17 +1344,20 @@ void SceneGraph::serialize(Archive& ar, const unsigned int version) std::ostream& operator<<(std::ostream& os, const ShortestPath& path) { - os << "Links:" << std::endl; + os << "Links:" + << "\n"; for (const auto& l : path.links) - os << " " << l << std::endl; + os << " " << l << "\n"; - os << "Joints:" << std::endl; + os << "Joints:" + << "\n"; for (const auto& j : path.joints) - os << " " << j << std::endl; + os << " " << j << "\n"; - os << "Active Joints:" << std::endl; + os << "Active Joints:" + << "\n"; for (const auto& j : path.active_joints) - os << " " << j << std::endl; + os << " " << j << "\n"; return os; } diff --git a/tesseract_scene_graph/src/kdl_parser.cpp b/tesseract_scene_graph/src/kdl_parser.cpp index 63ad237e409..566613ec9d7 100644 --- a/tesseract_scene_graph/src/kdl_parser.cpp +++ b/tesseract_scene_graph/src/kdl_parser.cpp @@ -290,7 +290,7 @@ struct kdl_tree_builder : public boost::dfs_visitor<> } protected: - KDLTreeData& data_; + KDLTreeData& data_; // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members) }; /** @@ -443,14 +443,16 @@ struct kdl_sub_tree_builder : public boost::dfs_visitor<> } protected: - KDLTreeData& data_; + KDLTreeData& data_; // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members) int search_cnt_{ -1 }; bool started_{ false }; std::map segment_transforms_; std::vector link_names_; - const std::vector& joint_names_; + const std::vector& joint_names_; // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members) + // NOLINTNEXTLINE(cppcoreguidelines-avoid-const-or-ref-data-members) const std::unordered_map& joint_values_; + // NOLINTNEXTLINE(cppcoreguidelines-avoid-const-or-ref-data-members) const tesseract_common::TransformMap& floating_joint_values_; }; diff --git a/tesseract_scene_graph/test/tesseract_scene_graph_unit.cpp b/tesseract_scene_graph/test/tesseract_scene_graph_unit.cpp index 1bc7d64a270..c9abe41c74d 100644 --- a/tesseract_scene_graph/test/tesseract_scene_graph_unit.cpp +++ b/tesseract_scene_graph/test/tesseract_scene_graph_unit.cpp @@ -163,24 +163,24 @@ void runTest(tesseract_scene_graph::SceneGraph& g) g.saveDOT(tesseract_common::getTempPath() + "graph_acyclic_tree_example.dot"); // Test if the graph is Acyclic - std::cout << "Is Acyclic: " << g.isAcyclic() << std::endl; + std::cout << "Is Acyclic: " << g.isAcyclic() << "\n"; EXPECT_TRUE(g.isAcyclic()); // Test if the graph is Tree - std::cout << "Is Tree: " << g.isTree() << std::endl; + std::cout << "Is Tree: " << g.isTree() << "\n"; EXPECT_TRUE(g.isTree()); // Test for unused links Link link_6("link_6"); g.addLink(link_6); - std::cout << "Free Link, Is Tree: " << g.isTree() << std::endl; + std::cout << "Free Link, Is Tree: " << g.isTree() << "\n"; EXPECT_FALSE(g.isTree()); // Check Graph checkSceneGraph(g); g.removeLink("link_6"); - std::cout << "Free Link Removed, Is Tree: " << g.isTree() << std::endl; + std::cout << "Free Link Removed, Is Tree: " << g.isTree() << "\n"; EXPECT_TRUE(g.isTree()); // Check Graph @@ -200,11 +200,11 @@ void runTest(tesseract_scene_graph::SceneGraph& g) g.saveDOT(tesseract_common::getTempPath() + "graph_acyclic_not_tree_example.dot"); // Test if the graph is Acyclic - std::cout << "Is Acyclic: " << g.isAcyclic() << std::endl; + std::cout << "Is Acyclic: " << g.isAcyclic() << "\n"; EXPECT_TRUE(g.isAcyclic()); // Test if the graph is Tree - std::cout << "Is Tree: " << g.isTree() << std::endl; + std::cout << "Is Tree: " << g.isTree() << "\n"; EXPECT_FALSE(g.isTree()); Joint joint_6("joint_6"); @@ -221,17 +221,17 @@ void runTest(tesseract_scene_graph::SceneGraph& g) g.saveDOT(tesseract_common::getTempPath() + "graph_cyclic_not_tree_example.dot"); // Test if the graph is Acyclic - std::cout << "Is Acyclic: " << g.isAcyclic() << std::endl; + std::cout << "Is Acyclic: " << g.isAcyclic() << "\n"; EXPECT_FALSE(g.isAcyclic()); // Test if the graph is Tree - std::cout << "Is Tree: " << g.isTree() << std::endl; + std::cout << "Is Tree: " << g.isTree() << "\n"; EXPECT_FALSE(g.isTree()); { // Get Shortest Path ShortestPath path = g.getShortestPath("link_1", "link_4"); - std::cout << path << std::endl; + std::cout << path << "\n"; EXPECT_TRUE(path.links.size() == 3); EXPECT_TRUE(std::find(path.links.begin(), path.links.end(), "link_1") != path.links.end()); EXPECT_TRUE(std::find(path.links.begin(), path.links.end(), "link_5") != path.links.end()); @@ -243,13 +243,13 @@ void runTest(tesseract_scene_graph::SceneGraph& g) EXPECT_TRUE(std::find(path.active_joints.begin(), path.active_joints.end(), "joint_5") != path.active_joints.end()); EXPECT_TRUE(std::find(path.active_joints.begin(), path.active_joints.end(), "joint_6") != path.active_joints.end()); - std::cout << (g.getName().c_str()) << std::endl; + std::cout << (g.getName().c_str()) << "\n"; } { // Get Shortest Path wit links reversed ShortestPath path = g.getShortestPath("link_4", "link_1"); - std::cout << path << std::endl; + std::cout << path << "\n"; EXPECT_TRUE(path.links.size() == 3); EXPECT_TRUE(std::find(path.links.begin(), path.links.end(), "link_1") != path.links.end()); EXPECT_TRUE(std::find(path.links.begin(), path.links.end(), "link_5") != path.links.end()); @@ -261,7 +261,7 @@ void runTest(tesseract_scene_graph::SceneGraph& g) EXPECT_TRUE(std::find(path.active_joints.begin(), path.active_joints.end(), "joint_5") != path.active_joints.end()); EXPECT_TRUE(std::find(path.active_joints.begin(), path.active_joints.end(), "joint_6") != path.active_joints.end()); - std::cout << (g.getName().c_str()) << std::endl; + std::cout << (g.getName().c_str()) << "\n"; } // Should throw since this is a directory and not a file @@ -802,7 +802,7 @@ TEST(TesseractSceneGraphUnit, TesseractSceneGraphRemoveJointUnit) // NOLINT void printKDLTree(const KDL::SegmentMap::const_iterator& link, const std::string& prefix) { std::cout << prefix << "- Segment " << GetTreeElementSegment(link->second).getName() << " has " - << GetTreeElementChildren(link->second).size() << " children" << std::endl; + << GetTreeElementChildren(link->second).size() << " children\n"; for (auto child : GetTreeElementChildren(link->second)) printKDLTree(child, prefix + " "); @@ -1171,9 +1171,9 @@ TEST(TesseractSceneGraphUnit, LoadKDLUnit) // NOLINT testSceneGraphKDLTree(data.tree); // walk through tree - std::cout << " ======================================" << std::endl; - std::cout << " Tree has " << data.tree.getNrOfSegments() << " link(s) and a root link" << std::endl; - std::cout << " ======================================" << std::endl; + std::cout << " ======================================\n"; + std::cout << " Tree has " << data.tree.getNrOfSegments() << " link(s) and a root link\n"; + std::cout << " ======================================\n"; auto root = data.tree.getRootSegment(); printKDLTree(root, ""); @@ -1201,9 +1201,9 @@ TEST(TesseractSceneGraphUnit, LoadKDLUnit) // NOLINT testSceneGraphKDLTree(data.tree); // walk through tree - std::cout << " ======================================" << std::endl; - std::cout << " Tree has " << data.tree.getNrOfSegments() << " link(s) and a root link" << std::endl; - std::cout << " ======================================" << std::endl; + std::cout << " ======================================\n"; + std::cout << " Tree has " << data.tree.getNrOfSegments() << " link(s) and a root link\n"; + std::cout << " ======================================\n"; auto root = data.tree.getRootSegment(); printKDLTree(root, ""); @@ -1248,9 +1248,9 @@ TEST(TesseractSceneGraphUnit, LoadSubKDLUnit) // NOLINT testSubSceneGraphKDLTree(data, full_data, joint_values); // walk through tree - std::cout << " ======================================" << std::endl; - std::cout << " Tree has " << data.tree.getNrOfSegments() << " link(s) and a root link" << std::endl; - std::cout << " ======================================" << std::endl; + std::cout << " ======================================\n"; + std::cout << " Tree has " << data.tree.getNrOfSegments() << " link(s) and a root link\n"; + std::cout << " ======================================\n"; auto root = data.tree.getRootSegment(); printKDLTree(root, ""); @@ -1279,9 +1279,9 @@ TEST(TesseractSceneGraphUnit, LoadSubKDLUnit) // NOLINT testSubSceneGraphKDLTree(data, full_data, joint_values); // walk through tree - std::cout << " ======================================" << std::endl; - std::cout << " Tree has " << data.tree.getNrOfSegments() << " link(s) and a root link" << std::endl; - std::cout << " ======================================" << std::endl; + std::cout << " ======================================\n"; + std::cout << " Tree has " << data.tree.getNrOfSegments() << " link(s) and a root link\n"; + std::cout << " ======================================\n"; auto root = data.tree.getRootSegment(); printKDLTree(root, ""); diff --git a/tesseract_srdf/test/tesseract_srdf_unit.cpp b/tesseract_srdf/test/tesseract_srdf_unit.cpp index c2d66d96bdb..433df7f7c99 100644 --- a/tesseract_srdf/test/tesseract_srdf_unit.cpp +++ b/tesseract_srdf/test/tesseract_srdf_unit.cpp @@ -12,7 +12,6 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP #include #include #include -#include #include #include #include @@ -25,7 +24,7 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP #include #include -enum class ABBConfig +enum class ABBConfig : std::uint8_t { ROBOT_ONLY, ROBOT_ON_RAIL, @@ -1772,7 +1771,7 @@ TEST(TesseractSRDFUnit, AddRemoveChainGroupUnit) // NOLINT // ADD ChainGroup chain_group; - chain_group.push_back(std::make_pair("base_link", "tool0")); + chain_group.emplace_back("base_link", "tool0"); info.addChainGroup("manipulator", chain_group); EXPECT_TRUE(info.hasChainGroup("manipulator")); EXPECT_TRUE(info.chain_groups.at("manipulator") == chain_group); @@ -1786,7 +1785,7 @@ TEST(TesseractSRDFUnit, AddRemoveChainGroupUnit) // NOLINT // Not equal chain_group = ChainGroup(); - chain_group.push_back(std::make_pair("tool0", "base_link")); + chain_group.emplace_back("tool0", "base_link"); info1_copy.addChainGroup("manipulator", chain_group); EXPECT_NE(info1_copy, info); diff --git a/tesseract_state_solver/src/ofkt_state_solver.cpp b/tesseract_state_solver/src/ofkt_state_solver.cpp index 9ec9253c1f9..36084c8b425 100644 --- a/tesseract_state_solver/src/ofkt_state_solver.cpp +++ b/tesseract_state_solver/src/ofkt_state_solver.cpp @@ -73,8 +73,8 @@ struct ofkt_builder : public boost::dfs_visitor<> } protected: - OFKTStateSolver& tree_; - std::vector& new_joints_limits_; + OFKTStateSolver& tree_; // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members) + std::vector& new_joints_limits_; // NOLINT(cppcoreguidelines-avoid-const-or-ref-data-members) std::string prefix_; }; diff --git a/tesseract_urdf/CMakeLists.txt b/tesseract_urdf/CMakeLists.txt index 1a6f1c358f5..9e2432eda1f 100644 --- a/tesseract_urdf/CMakeLists.txt +++ b/tesseract_urdf/CMakeLists.txt @@ -84,14 +84,6 @@ target_link_libraries(${PROJECT_NAME} PRIVATE Boost::boost console_bridge::conso target_compile_options(${PROJECT_NAME} PRIVATE ${TESSERACT_COMPILE_OPTIONS_PRIVATE}) target_compile_options(${PROJECT_NAME} PUBLIC ${TESSERACT_COMPILE_OPTIONS_PUBLIC}) target_compile_definitions(${PROJECT_NAME} PUBLIC ${TESSERACT_COMPILE_DEFINITIONS}) -target_clang_tidy(${PROJECT_NAME} ENABLE ${TESSERACT_ENABLE_CLANG_TIDY}) -target_cxx_version(${PROJECT_NAME} PUBLIC VERSION ${TESSERACT_CXX_VERSION}) -target_code_coverage( - ${PROJECT_NAME} - PRIVATE - ALL - EXCLUDE ${COVERAGE_EXCLUDE} - ENABLE ${TESSERACT_ENABLE_CODE_COVERAGE}) # PCL does not support c++11 on Xenial so cannot include point cloud parsing from urdf Boost version number is in XYYYZZ # format such that: (BOOST_VERSION % 100) is the sub-minor version ((BOOST_VERSION / 100) % 1000) is the minor version @@ -103,6 +95,7 @@ else(TESSERACT_Boost_VERSION_MACRO ${Boost_VERSION_MACRO}) endif() if(TESSERACT_Boost_VERSION_MACRO VERSION_GREATER "106000") target_link_libraries(${PROJECT_NAME} PUBLIC ${PCL_IO_LIBRARIES} ${PCL_COMMON_LIBRARIES}) + target_include_directories(${PROJECT_NAME} SYSTEM PUBLIC ${PCL_INCLUDE_DIRS}) target_compile_definitions(${PROJECT_NAME} PUBLIC TESSERACT_PARSE_POINT_CLOUDS="ON") foreach(DEF ${PCL_DEFINITIONS}) string(STRIP ${DEF} DEF) @@ -129,14 +122,20 @@ if(TESSERACT_Boost_VERSION_MACRO VERSION_GREATER "106000") endif() endif() endforeach() - if(NOT TARGET pcl_common) - target_include_directories(${PROJECT_NAME} SYSTEM PUBLIC ${PCL_INCLUDE_DIRS}) - endif() endif() target_include_directories(${PROJECT_NAME} PUBLIC "$" "$") +target_clang_tidy(${PROJECT_NAME} ENABLE ${TESSERACT_ENABLE_CLANG_TIDY}) +target_cxx_version(${PROJECT_NAME} PUBLIC VERSION ${TESSERACT_CXX_VERSION}) +target_code_coverage( + ${PROJECT_NAME} + PRIVATE + ALL + EXCLUDE ${COVERAGE_EXCLUDE} + ENABLE ${TESSERACT_ENABLE_CODE_COVERAGE}) + configure_package( NAMESPACE tesseract TARGETS ${PROJECT_NAME} diff --git a/tesseract_urdf/test/tesseract_urdf_urdf_unit.cpp b/tesseract_urdf/test/tesseract_urdf_urdf_unit.cpp index 010d5dffba7..5e6be4327cf 100644 --- a/tesseract_urdf/test/tesseract_urdf_urdf_unit.cpp +++ b/tesseract_urdf/test/tesseract_urdf_urdf_unit.cpp @@ -422,7 +422,7 @@ TEST(TesseractURDFUnit, LoadURDFUnit) // NOLINT // Get Shortest Path auto path = g->getShortestPath("link_1", "link_4"); - std::cout << path << std::endl; + std::cout << path << "\n"; EXPECT_TRUE(path.links.size() == 4); EXPECT_TRUE(std::find(path.links.begin(), path.links.end(), "link_1") != path.links.end()); EXPECT_TRUE(std::find(path.links.begin(), path.links.end(), "link_2") != path.links.end()); diff --git a/tesseract_visualization/src/ignition/tesseract_ignition_visualization.cpp b/tesseract_visualization/src/ignition/tesseract_ignition_visualization.cpp index cba5cac3be6..97296864010 100644 --- a/tesseract_visualization/src/ignition/tesseract_ignition_visualization.cpp +++ b/tesseract_visualization/src/ignition/tesseract_ignition_visualization.cpp @@ -332,7 +332,7 @@ void TesseractIgnitionVisualization::plotMarker(const Marker& marker, std::strin } default: { - ignwarn << "plotMarkers: Unsupported marker type: " << std::to_string(marker.getType()) << std::endl; + ignwarn << "plotMarkers: Unsupported marker type: " << std::to_string(marker.getType()) << "\n"; } } } @@ -340,7 +340,7 @@ void TesseractIgnitionVisualization::plotMarker(const Marker& marker, std::strin void TesseractIgnitionVisualization::plotMarkers(const std::vector >& /*markers*/, std::string /*ns*/) { - ignerr << "plotMarkers is currently not implemented!" << std::endl; + ignerr << "plotMarkers is currently not implemented!\n"; } void TesseractIgnitionVisualization::clear(std::string /*ns*/) @@ -363,7 +363,7 @@ void TesseractIgnitionVisualization::clear(std::string /*ns*/) void TesseractIgnitionVisualization::waitForInput(std::string message) { - std::cout << message << std::endl; + std::cout << message << "\n"; std::cin.ignore(std::numeric_limits::max(), '\n'); } @@ -380,7 +380,7 @@ void TesseractIgnitionVisualization::sendSceneState(const tesseract_scene_graph: if (!pose_pub_.Publish(pose_v)) { - ignerr << "Failed to publish pose vector!" << std::endl; + ignerr << "Failed to publish pose vector!\n"; } } @@ -402,7 +402,7 @@ void TesseractIgnitionVisualization::sendSceneState(const tesseract_scene_graph: // } // else // { -// ignerr << "plotTrajectoy: Unsupported Instruction Type!" << std::endl; +// ignerr << "plotTrajectoy: Unsupported Instruction Type!\n"; // return; // } @@ -427,7 +427,7 @@ void TesseractIgnitionVisualization::sendSceneState(const tesseract_scene_graph: // } // else // { -// ignerr << "plotTrajectoy: Unsupported Waypoint Type!" << std::endl; +// ignerr << "plotTrajectoy: Unsupported Waypoint Type!\n"; // } // } //} @@ -455,7 +455,7 @@ void TesseractIgnitionVisualization::sendSceneState(const tesseract_scene_graph: // auto composite_mi_fwd_kin = env_->getManipulatorManager()->getFwdKinematicSolver(composite_mi.manipulator); // if (composite_mi_fwd_kin == nullptr) // { -// ignerr << "plotToolPath: Manipulator: " << composite_mi.manipulator << " does not exist!" << std::endl; +// ignerr << "plotToolPath: Manipulator: " << composite_mi.manipulator << " does not exist!\n"; // return; // } // const std::string& tip_link = composite_mi_fwd_kin->getTipLinkName(); @@ -526,7 +526,7 @@ void TesseractIgnitionVisualization::sendSceneState(const tesseract_scene_graph: // } // else // { -// ignerr << "plotTrajectoy: Unsupported Waypoint Type!" << std::endl; +// ignerr << "plotTrajectoy: Unsupported Waypoint Type!\n"; // } // } // } @@ -549,7 +549,7 @@ void TesseractIgnitionVisualization::sendSceneState(const tesseract_scene_graph: // auto composite_mi_fwd_kin = env_->getManipulatorManager()->getFwdKinematicSolver(manip_info.manipulator); // if (composite_mi_fwd_kin == nullptr) // { -// ignerr << "plotToolPath: Manipulator: " << manip_info.manipulator << " does not exist!" << std::endl; +// ignerr << "plotToolPath: Manipulator: " << manip_info.manipulator << " does not exist!\n"; // return; // } // const std::string& tip_link = composite_mi_fwd_kin->getTipLinkName(); @@ -591,12 +591,12 @@ void TesseractIgnitionVisualization::sendSceneState(const tesseract_scene_graph: // } // else // { -// ignerr << "plotTrajectoy: Unsupported Waypoint Type!" << std::endl; +// ignerr << "plotTrajectoy: Unsupported Waypoint Type!\n"; // } // } // else // { -// ignerr << "plotTrajectoy: Unsupported Instruction Type!" << std::endl; +// ignerr << "plotTrajectoy: Unsupported Instruction Type!\n" l; // } // scene_pub_.Publish(scene_msg);