diff --git a/.clang-tidy b/.clang-tidy index 830da525463..b90b8f8f1ed 100644 --- a/.clang-tidy +++ b/.clang-tidy @@ -21,9 +21,13 @@ Checks: > misc-*, -misc-non-private-member-variables-in-classes, -misc-no-recursion, + -misc-const-correctness, + -misc-include-cleaner, + -misc-use-internal-linkage, modernize-*, -modernize-use-trailing-return-type, -modernize-use-nodiscard, + -modernize-type-traits, performance-*, readability-*, -readability-braces-around-statements, @@ -56,9 +60,13 @@ WarningsAsErrors: > misc-*, -misc-non-private-member-variables-in-classes, -misc-no-recursion, + -misc-const-correctness, + -misc-include-cleaner, + -misc-use-internal-linkage, modernize-*, -modernize-use-trailing-return-type, -modernize-use-nodiscard, + -modernize-type-traits, performance-*, readability-*, -readability-braces-around-statements, @@ -80,4 +88,6 @@ CheckOptions: value: '1' - key: cppcoreguidelines-pro-type-member-init.IgnoreArrays value: '1' +ExtraArgs: + - '-std=c++17' ... 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/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_utils.cpp b/tesseract_collision/bullet/src/bullet_utils.cpp index 82e1d55875a..0117f5dd59a 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) @@ -233,12 +233,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; } 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/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/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_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/plugin_loader.hpp b/tesseract_common/include/tesseract_common/plugin_loader.hpp index 21e9bbddca7..4fc0aea14de 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 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..a867c1c659f 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); 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_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/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/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/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_scene_graph/src/graph.cpp b/tesseract_scene_graph/src/graph.cpp index bd87dbeec69..23613fe175c 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(std::move(static_cast(other))) , link_map_(std::move(other.link_map_)) , joint_map_(std::move(other.joint_map_)) , acm_(std::move(other.acm_)) @@ -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_srdf/test/tesseract_srdf_unit.cpp b/tesseract_srdf/test/tesseract_srdf_unit.cpp index c2d66d96bdb..4bcaeb44b6b 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