Skip to content

Commit

Permalink
Fix clang-tidy-21 errors
Browse files Browse the repository at this point in the history
  • Loading branch information
Levi-Armstrong committed Feb 6, 2025
1 parent a553b90 commit 64bce54
Show file tree
Hide file tree
Showing 29 changed files with 78 additions and 64 deletions.
10 changes: 10 additions & 0 deletions .clang-tidy
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand Down Expand Up @@ -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,
Expand All @@ -80,4 +88,6 @@ CheckOptions:
value: '1'
- key: cppcoreguidelines-pro-type-member-init.IgnoreArrays
value: '1'
ExtraArgs:
- '-std=c++17'
...
Original file line number Diff line number Diff line change
Expand Up @@ -74,9 +74,9 @@ class BulletCollisionShapeCache

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

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,9 @@
namespace tesseract_collision::tesseract_collision_bullet
{
// Static member definitions
// NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables)
std::map<boost::uuids::uuid, std::weak_ptr<BulletCollisionShape>> BulletCollisionShapeCache::cache_;
// NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables)
std::mutex BulletCollisionShapeCache::mutex_;

BulletCollisionShape::BulletCollisionShape(std::shared_ptr<btCollisionShape> top_level_)
Expand Down
22 changes: 11 additions & 11 deletions tesseract_collision/bullet/src/bullet_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -127,23 +127,23 @@ std::shared_ptr<BulletCollisionShape> createShapePrimitive(const tesseract_geome

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

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

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

std::shared_ptr<BulletCollisionShape> createShapePrimitive(const tesseract_geometry::Mesh::ConstPtr& geom)
Expand Down Expand Up @@ -233,12 +233,12 @@ std::shared_ptr<BulletCollisionShape> createShapePrimitive(const tesseract_geome
geomTrans.setIdentity();
geomTrans.setOrigin(btVector3(
static_cast<btScalar>(it.getX()), static_cast<btScalar>(it.getY()), static_cast<btScalar>(it.getZ())));
auto l = static_cast<btScalar>(size / 2.0);
auto length = static_cast<btScalar>(size / 2.0);

std::shared_ptr<btCollisionShape> childshape = managed_shapes.at(it.getDepth());
if (childshape == nullptr)
{
childshape = std::make_shared<btBoxShape>(btVector3(l, l, l));
childshape = std::make_shared<btBoxShape>(btVector3(length, length, length));
childshape->setMargin(BULLET_MARGIN);
managed_shapes.at(it.getDepth()) = childshape;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,7 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP
#include <tesseract_collision/core/discrete_contact_manager.h>
#include <tesseract_collision/core/continuous_contact_manager.h>
#include <tesseract_common/resource_locator.h>
#include <tesseract_common/plugin_loader.hpp>
#include <tesseract_common/plugin_loader.h>
#include <tesseract_common/yaml_utils.h>
#include <tesseract_common/yaml_extenstions.h>
#include <tesseract_collision/core/contact_managers_plugin_factory.h>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -64,9 +64,9 @@ class FCLCollisionGeometryCache

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

Expand Down
2 changes: 2 additions & 0 deletions tesseract_collision/fcl/src/fcl_collision_geometry_cache.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,9 @@
namespace tesseract_collision::tesseract_collision_fcl
{
// Static member definitions
// NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables)
std::map<boost::uuids::uuid, std::weak_ptr<fcl::CollisionGeometryd>> FCLCollisionGeometryCache::cache_;
// NOLINTNEXTLINE(cppcoreguidelines-avoid-non-const-global-variables)
std::mutex FCLCollisionGeometryCache::mutex_;

void FCLCollisionGeometryCache::insert(const std::shared_ptr<const tesseract_geometry::Geometry>& key,
Expand Down
2 changes: 0 additions & 2 deletions tesseract_common/include/tesseract_common/class_loader.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,8 +37,6 @@ TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
#include <console_bridge/console.h>
TESSERACT_COMMON_IGNORE_WARNINGS_POP

#include <tesseract_common/class_loader.h>

namespace tesseract_common
{
template <class ClassBase>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,6 @@ TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
#include <ostream>
TESSERACT_COMMON_IGNORE_WARNINGS_POP

#include <tesseract_common/plugin_loader.h>
#include <tesseract_common/class_loader.h>

namespace tesseract_common
Expand Down
2 changes: 1 addition & 1 deletion tesseract_common/include/tesseract_common/serialization.h
Original file line number Diff line number Diff line change
Expand Up @@ -197,7 +197,7 @@ struct Serialization
}

std::string data = ss.str();
return std::vector<std::uint8_t>(data.begin(), data.end());
return { data.begin(), data.end() };
}

template <typename SerializableType>
Expand Down
2 changes: 1 addition & 1 deletion tesseract_common/include/tesseract_common/utils.h
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP

namespace tinyxml2
{
class XMLElement;
class XMLElement; // NOLINT
class XMLAttribute;
} // namespace tinyxml2

Expand Down
2 changes: 1 addition & 1 deletion tesseract_common/src/allowed_collision_matrix.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
5 changes: 1 addition & 4 deletions tesseract_common/src/collision_margin_data.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
5 changes: 4 additions & 1 deletion tesseract_common/src/joint_state.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<value_type> l)
{
return states.insert(p, l);
Expand Down
2 changes: 1 addition & 1 deletion tesseract_common/src/resource_locator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -332,7 +332,7 @@ std::shared_ptr<std::istream> BytesResource::getResourceContentStream() const
{
std::shared_ptr<std::stringstream> o = std::make_shared<std::stringstream>();
o->write((const char*)&bytes_.at(0), static_cast<std::streamsize>(bytes_.size())); // NOLINT
o->seekg(0, o->beg);
o->seekg(0, std::stringstream::beg);
return o;
}

Expand Down
14 changes: 7 additions & 7 deletions tesseract_common/src/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down Expand Up @@ -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);
Expand All @@ -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<unsigned>(2 * level), ' ') << "exception: " << e.what() << std::endl;
std::cerr << std::string(static_cast<unsigned>(2 * level), ' ') << "exception: " << e.what() << "\n";
try
{
my_rethrow_if_nested(e);
Expand All @@ -254,7 +254,7 @@ void printNestedException(const std::exception& e, int level) // NOLINT(misc-no
{
printNestedException(e, level + 1);
}
catch (...)
catch (...) // NOLINT
{
}
}
Expand All @@ -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<std::string>& sv)
Expand Down
2 changes: 1 addition & 1 deletion tesseract_common/test/plugin_loader_unit.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ TEST(TesseractClassLoaderUnit, LoadTestPlugin) // NOLINT
const std::string symbol_name = "plugin";

{
std::vector<std::string> sections = ClassLoader::getAvailableSections(lib_name, lib_dir);
std::vector<std::string> sections = ClassLoader::getAvailableSections(lib_name, lib_dir); // NOLINT
EXPECT_EQ(sections.size(), 1);
EXPECT_EQ(sections.at(0), "TestBase");

Expand Down
6 changes: 2 additions & 4 deletions tesseract_common/test/tesseract_common_unit.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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__);
Expand Down Expand Up @@ -263,10 +262,9 @@ TEST(TesseractCommonUnit, sfinaeHasMemberFunctionSignature) // NOLINT
TEST(TesseractCommonUnit, bytesResource) // NOLINT
{
std::vector<uint8_t> data;
data.reserve(8);
for (uint8_t i = 0; i < 8; i++)
{
data.push_back(i);
}

std::shared_ptr<tesseract_common::BytesResource> bytes_resource =
std::make_shared<tesseract_common::BytesResource>("package://test_package/data.bin", data);
Expand Down Expand Up @@ -466,7 +464,7 @@ template <typename T>
void runAnyPolyUnorderedMapIntegralTest(T value, const std::string& type_str)
{
std::unordered_map<std::string, T> 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<std::string, T>)));
bool check = any_type.as<std::unordered_map<std::string, T>>() == data;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ class Capsule : public Geometry
using Ptr = std::shared_ptr<Capsule>;
using ConstPtr = std::shared_ptr<const Capsule>;

Capsule(double r, double l);
Capsule(double radius, double length);
Capsule() = default;
~Capsule() override = default;

Expand Down
2 changes: 1 addition & 1 deletion tesseract_geometry/include/tesseract_geometry/impl/cone.h
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ class Cone : public Geometry
using Ptr = std::shared_ptr<Cone>;
using ConstPtr = std::shared_ptr<const Cone>;

Cone(double r, double l);
Cone(double radius, double length);
Cone() = default;
~Cone() override = default;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ class Cylinder : public Geometry
using Ptr = std::shared_ptr<Cylinder>;
using ConstPtr = std::shared_ptr<const Cylinder>;

Cylinder(double r, double l);
Cylinder(double radius, double length);
Cylinder() = default;
~Cylinder() override = default;

Expand Down
2 changes: 1 addition & 1 deletion tesseract_geometry/src/geometries/capsule.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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_; }
Expand Down
2 changes: 1 addition & 1 deletion tesseract_geometry/src/geometries/cone.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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_; }
Expand Down
2 changes: 1 addition & 1 deletion tesseract_geometry/src/geometries/cylinder.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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_; }
Expand Down
1 change: 0 additions & 1 deletion tesseract_geometry/src/geometry.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,4 +55,3 @@ void Geometry::serialize(Archive& ar, const unsigned int /*version*/)
} // namespace tesseract_geometry

TESSERACT_SERIALIZE_ARCHIVES_INSTANTIATE(tesseract_geometry::Geometry)
#include <tesseract_common/serialization.h>
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP
#include <tesseract_scene_graph/graph.h>
#include <tesseract_scene_graph/scene_state.h>
#include <tesseract_common/resource_locator.h>
#include <tesseract_common/plugin_loader.hpp>
#include <tesseract_common/plugin_loader.h>
#include <tesseract_common/yaml_utils.h>
#include <tesseract_common/yaml_extenstions.h>
#include <tesseract_kinematics/core/kinematics_plugin_factory.h>
Expand Down
Loading

0 comments on commit 64bce54

Please sign in to comment.