Skip to content
New issue

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

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

Already on GitHub? Sign in to your account

Add new clang-tidy style rules #2177

Merged
merged 10 commits into from
Oct 27, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 8 additions & 0 deletions .clang-tidy
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@ Checks: '-*,
readability-simplify-boolean-expr,
readability-container-size-empty,
readability-identifier-naming,
readability-static-definition-in-anonymous-namespace,
'
HeaderFilterRegex: ''
AnalyzeTemporaryDtors: false
Expand All @@ -37,6 +38,9 @@ CheckOptions:
value: CamelCase
- key: readability-identifier-naming.UnionCase
value: CamelCase
# function names
- key: readability-identifier-naming.FunctionCase
value: camelBack
# method names
- key: readability-identifier-naming.MethodCase
value: camelBack
Expand All @@ -50,8 +54,12 @@ CheckOptions:
# const static or global variables are UPPER_CASE
- key: readability-identifier-naming.EnumConstantCase
value: UPPER_CASE
- key: readability-identifier-naming.StaticVariableCasePrefix
value: 's_'
Comment on lines +57 to +58
Copy link
Contributor

Choose a reason for hiding this comment

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

Please don't add prefixes or suffixes to variable names. Marking static variables via UPPER_CASE should be sufficient.

Copy link
Member

Choose a reason for hiding this comment

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

What about the case where the static variable is mutable and not a constant?

Copy link
Contributor

Choose a reason for hiding this comment

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

So far, we just had lower_case names for them.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Our conclusion in the maintainer meeting was that we'd like to mark mutable static variables due to their impact on thread safety. Having a unique naming rule will give them more visibility for reviewers and developers. However, there was no strong preference for a specific naming rule. What would be your reasoning against a unique naming rule and if you don't have any objections, which naming convention would you prefere?

Copy link
Contributor

Choose a reason for hiding this comment

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

If you want to mark mutable static variables, using a prefix s_ is probably the way to go. Note that this will require many code changes, which all should be part of this PR.

Copy link
Member

Choose a reason for hiding this comment

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

I hope that, generally, we don't use mutable static variables except in some generic code for edge cases. I don't know if that is true though :/

- key: readability-identifier-naming.StaticConstantCase
value: UPPER_CASE
- key: readability-identifier-naming.GlobalConstantCase
value: UPPER_CASE
- key: readability-identifier-naming.ClassConstantCase
value: UPPER_CASE
...
10 changes: 5 additions & 5 deletions moveit_core/collision_detection/test/test_world.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -224,7 +224,7 @@ struct TestAction
};

/* notification callback */
static void TrackChangesNotify(TestAction& ta, const World::ObjectConstPtr& obj, World::Action action)
static void trackChangesNotify(TestAction& ta, const World::ObjectConstPtr& obj, World::Action action)
{
ta.obj_ = *obj;
ta.action_ = action;
Expand All @@ -238,7 +238,7 @@ TEST(World, TrackChanges)
TestAction ta;
World::ObserverHandle observer_ta;
observer_ta = world.addObserver([&ta](const World::ObjectConstPtr& object, World::Action action) {
return TrackChangesNotify(ta, object, action);
return trackChangesNotify(ta, object, action);
});

// Create some shapes
Expand Down Expand Up @@ -271,7 +271,7 @@ TEST(World, TrackChanges)
TestAction ta2;
World::ObserverHandle observer_ta2;
observer_ta2 = world.addObserver([&ta2](const World::ObjectConstPtr& object, World::Action action) {
return TrackChangesNotify(ta2, object, action);
return trackChangesNotify(ta2, object, action);
});

world.addToObject("obj2", cyl, Eigen::Isometry3d::Identity());
Expand Down Expand Up @@ -311,7 +311,7 @@ TEST(World, TrackChanges)
TestAction ta3;
World::ObserverHandle observer_ta3;
observer_ta3 = world.addObserver([&ta3](const World::ObjectConstPtr& object, World::Action action) {
return TrackChangesNotify(ta3, object, action);
return trackChangesNotify(ta3, object, action);
});

bool rm_good = world.removeShapeFromObject("obj2", cyl);
Expand Down Expand Up @@ -379,7 +379,7 @@ TEST(World, ObjectPoseAndSubframes)
TestAction ta;
World::ObserverHandle observer_ta;
observer_ta = world.addObserver([&ta](const World::ObjectConstPtr& object, World::Action action) {
return TrackChangesNotify(ta, object, action);
return trackChangesNotify(ta, object, action);
});

// Create shapes
Expand Down
12 changes: 6 additions & 6 deletions moveit_core/collision_detection_fcl/src/collision_common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -709,7 +709,7 @@ bool distanceCallback(fcl::CollisionObjectd* o1, fcl::CollisionObjectd* o2, void
*
* The returned cache is a quasi-singleton for each thread as it is created \e thread_local. */
template <typename BV, typename T>
FCLShapeCache& GetShapeCache()
FCLShapeCache& getShapeCache()
{
/* The cache is created thread_local, that is each thread calling
* this quasi-singleton function will get its own instance. Once
Expand All @@ -735,7 +735,7 @@ FCLGeometryConstPtr createCollisionGeometry(const shapes::ShapeConstPtr& shape,
using ShapeKey = shapes::ShapeConstWeakPtr;
using ShapeMap = std::map<ShapeKey, FCLGeometryConstPtr, std::owner_less<ShapeKey>>;

FCLShapeCache& cache = GetShapeCache<BV, T>();
FCLShapeCache& cache = getShapeCache<BV, T>();

shapes::ShapeConstWeakPtr wptr(shape);
{
Expand Down Expand Up @@ -767,7 +767,7 @@ FCLGeometryConstPtr createCollisionGeometry(const shapes::ShapeConstPtr& shape,
if (std::is_same<T, moveit::core::AttachedBody>::value)
{
// get the cache that corresponds to objects; maybe this attached object used to be a world object
FCLShapeCache& othercache = GetShapeCache<BV, World::Object>();
FCLShapeCache& othercache = getShapeCache<BV, World::Object>();

// attached bodies could be just moved from the environment.
auto cache_it = othercache.map_.find(wptr);
Expand Down Expand Up @@ -800,7 +800,7 @@ FCLGeometryConstPtr createCollisionGeometry(const shapes::ShapeConstPtr& shape,
if (std::is_same<T, World::Object>::value)
{
// get the cache that corresponds to objects; maybe this attached object used to be a world object
FCLShapeCache& othercache = GetShapeCache<BV, moveit::core::AttachedBody>();
FCLShapeCache& othercache = getShapeCache<BV, moveit::core::AttachedBody>();

// attached bodies could be just moved from the environment.
auto cache_it = othercache.map_.find(wptr);
Expand Down Expand Up @@ -966,11 +966,11 @@ FCLGeometryConstPtr createCollisionGeometry(const shapes::ShapeConstPtr& shape,

void cleanCollisionGeometryCache()
{
FCLShapeCache& cache1 = GetShapeCache<fcl::OBBRSSd, World::Object>();
FCLShapeCache& cache1 = getShapeCache<fcl::OBBRSSd, World::Object>();
{
cache1.bumpUseCount(true);
}
FCLShapeCache& cache2 = GetShapeCache<fcl::OBBRSSd, moveit::core::AttachedBody>();
FCLShapeCache& cache2 = getShapeCache<fcl::OBBRSSd, moveit::core::AttachedBody>();
{
cache2.bumpUseCount(true);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -105,7 +105,7 @@ void PR2ArmIKSolver::updateInternalDataStructures()
int PR2ArmIKSolver::CartToJnt(const KDL::JntArray& q_init, const KDL::Frame& p_in, KDL::JntArray& q_out)
{
const bool verbose = false;
Eigen::Isometry3f b = KDLToEigenMatrix(p_in);
Eigen::Isometry3f b = kdlToEigenMatrix(p_in);
std::vector<std::vector<double> > solution_ik;
if (free_angle_ == 0)
{
Expand Down Expand Up @@ -221,7 +221,7 @@ bool getKDLChain(const urdf::ModelInterface& model, const std::string& root_name
return true;
}

Eigen::Isometry3f KDLToEigenMatrix(const KDL::Frame& p)
Eigen::Isometry3f kdlToEigenMatrix(const KDL::Frame& p)
{
Eigen::Isometry3f b = Eigen::Isometry3f::Identity();
for (int i = 0; i < 3; ++i)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -115,7 +115,7 @@ class PR2ArmIKSolver : public KDL::ChainIkSolverPos
std::string root_frame_name_;
};

Eigen::Isometry3f KDLToEigenMatrix(const KDL::Frame& p);
Eigen::Isometry3f kdlToEigenMatrix(const KDL::Frame& p);
double computeEuclideanDistance(const std::vector<double>& array_1, const KDL::JntArray& array_2);
void getKDLChainInfo(const KDL::Chain& chain, moveit_msgs::msg::KinematicSolverInfo& chain_info);

Expand Down
18 changes: 9 additions & 9 deletions moveit_core/distance_field/test/test_distance_field.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ static const Eigen::Vector3d POINT1(0.1, 0.0, 0.0);
static const Eigen::Vector3d POINT2(0.0, 0.1, 0.2);
static const Eigen::Vector3d POINT3(0.4, 0.0, 0.0);

int dist_sq(int x, int y, int z)
int distanceSequence(int x, int y, int z)
{
return x * x + y * y + z * z;
}
Expand Down Expand Up @@ -295,8 +295,8 @@ unsigned int countLeafNodes(const octomap::OcTree& octree)
}

// points should contain all occupied points
void check_distance_field(const PropagationDistanceField& df, const EigenSTL::vector_Vector3d& points, int numX,
int numY, int numZ, bool do_negs)
void checkDistanceField(const PropagationDistanceField& df, const EigenSTL::vector_Vector3d& points, int numX, int numY,
int numZ, bool do_negs)
{
EigenSTL::vector_Vector3i points_ind(points.size());
for (unsigned int i = 0; i < points.size(); ++i)
Expand Down Expand Up @@ -374,15 +374,15 @@ TEST(TestPropagationDistanceField, TestAddRemovePoints)
// std::cout << "One removal, one addition" << '\n';
// print(df, numX, numY, numZ);
// printNeg(df, numX, numY, numZ);
check_distance_field(df, points, num_x, num_y, num_z, false);
checkDistanceField(df, points, num_x, num_y, num_z, false);

// Remove
points.clear();
points.push_back(POINT2);
df.removePointsFromField(points);
points.clear();
points.push_back(POINT3);
check_distance_field(df, points, num_x, num_y, num_z, false);
checkDistanceField(df, points, num_x, num_y, num_z, false);

// now testing gradient calls
df.reset();
Expand Down Expand Up @@ -455,7 +455,7 @@ TEST(TestSignedPropagationDistanceField, TestSignedAddRemovePoints)
// print(df, numX, numY, numZ);

// TODO - check initial values
// EXPECT_EQ( df.getCell(0,0,0).distance_square_, max_dist_sq_in_voxels );
// EXPECT_EQ( df.getCell(0,0,0).distance_square_, max_distanceSequence_in_voxels );

// Add points to the grid
double lwx, lwy, lwz;
Expand Down Expand Up @@ -627,7 +627,7 @@ TEST(TestSignedPropagationDistanceField, TestShape)
EigenSTL::vector_Vector3d point_vec;
findInternalPointsConvex(*body, RESOLUTION, point_vec);
delete body;
check_distance_field(df, point_vec, num_x, num_y, num_z, true);
checkDistanceField(df, point_vec, num_x, num_y, num_z, true);

// std::cout << "Shape pos "<< '\n';
// print(df, numX, numY, numZ);
Expand All @@ -644,12 +644,12 @@ TEST(TestSignedPropagationDistanceField, TestShape)
delete body;
EigenSTL::vector_Vector3d point_vec_union = point_vec_2;
point_vec_union.insert(point_vec_union.end(), point_vec.begin(), point_vec.end());
check_distance_field(df, point_vec_union, num_x, num_y, num_z, true);
checkDistanceField(df, point_vec_union, num_x, num_y, num_z, true);

// should get rid of old pose
df.moveShapeInField(&sphere, p, np);

check_distance_field(df, point_vec_2, num_x, num_y, num_z, true);
checkDistanceField(df, point_vec_2, num_x, num_y, num_z, true);

// should be equivalent to just adding second shape
PropagationDistanceField test_df(WIDTH, HEIGHT, DEPTH, RESOLUTION, ORIGIN_X, ORIGIN_Y, ORIGIN_Z, MAX_DIST, true);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -89,7 +89,7 @@ static double normalizeAbsoluteAngle(const double angle)
*/
template <typename Derived>
std::tuple<Eigen::Matrix<typename Eigen::MatrixBase<Derived>::Scalar, 3, 1>, bool>
CalcEulerAngles(const Eigen::MatrixBase<Derived>& R)
calcEulerAngles(const Eigen::MatrixBase<Derived>& R)
{
using std::atan2;
using std::sqrt;
Expand Down Expand Up @@ -721,11 +721,11 @@ ConstraintEvaluationResult OrientationConstraint::decide(const moveit::core::Rob
Eigen::Vector3d xyz_rotation;
if (parameterization_type_ == moveit_msgs::msg::OrientationConstraint::XYZ_EULER_ANGLES)
{
euler_angles_error = CalcEulerAngles(diff.linear());
euler_angles_error = calcEulerAngles(diff.linear());
// Converting from a rotation matrix to intrinsic XYZ Euler angles has 2 singularities:
// pitch ~= pi/2 ==> roll + yaw = theta
// pitch ~= -pi/2 ==> roll - yaw = theta
// in those cases CalcEulerAngles will set roll (xyz_rotation(0)) to theta and yaw (xyz_rotation(2)) to zero, so for
// in those cases calcEulerAngles will set roll (xyz_rotation(0)) to theta and yaw (xyz_rotation(2)) to zero, so for
// us to be able to capture yaw tolerance violations we do the following: If theta violates the absolute yaw
// tolerance we think of it as a pure yaw rotation and set roll to zero.
xyz_rotation = std::get<Eigen::Vector3d>(euler_angles_error);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -126,14 +126,14 @@ class FloatingJointRobot : public testing::Test
};

/** Helper function to create a quaternion from Euler angles. **/
inline Eigen::Quaterniond xyz_intrinsix_to_quat(double rx, double ry, double rz)
inline Eigen::Quaterniond xyzIntrinsixToQuaternion(double rx, double ry, double rz)
{
return Eigen::AngleAxisd(rx, Eigen::Vector3d::UnitX()) * Eigen::AngleAxisd(ry, Eigen::Vector3d::UnitY()) *
Eigen::AngleAxisd(rz, Eigen::Vector3d::UnitZ());
}

/** Helper function to create a quaternion from a rotation vector. **/
inline Eigen::Quaterniond rotation_vector_to_quat(double rx, double ry, double rz)
inline Eigen::Quaterniond rotationVectorToQuaternion(double rx, double ry, double rz)
{
Eigen::Vector3d v{ rx, ry, rz };
Eigen::Matrix3d m{ Eigen::AngleAxisd(v.norm(), v.normalized()) };
Expand Down Expand Up @@ -415,16 +415,16 @@ TEST_F(FloatingJointRobot, OrientationConstraintsParameterization)
EXPECT_TRUE(oc_rotvec.decide(robot_state, true).satisfied);

// some trivial test cases
setRobotEndEffectorOrientation(robot_state, xyz_intrinsix_to_quat(0.1, 0.2, -0.3));
setRobotEndEffectorOrientation(robot_state, xyzIntrinsixToQuaternion(0.1, 0.2, -0.3));
EXPECT_TRUE(oc_euler.decide(robot_state).satisfied);

setRobotEndEffectorOrientation(robot_state, xyz_intrinsix_to_quat(0.1, 0.2, -0.6));
setRobotEndEffectorOrientation(robot_state, xyzIntrinsixToQuaternion(0.1, 0.2, -0.6));
EXPECT_FALSE(oc_euler.decide(robot_state).satisfied);

setRobotEndEffectorOrientation(robot_state, rotation_vector_to_quat(0.1, 0.2, -0.3));
setRobotEndEffectorOrientation(robot_state, rotationVectorToQuaternion(0.1, 0.2, -0.3));
EXPECT_TRUE(oc_rotvec.decide(robot_state).satisfied);

setRobotEndEffectorOrientation(robot_state, rotation_vector_to_quat(0.1, 0.2, -0.6));
setRobotEndEffectorOrientation(robot_state, rotationVectorToQuaternion(0.1, 0.2, -0.6));
EXPECT_FALSE(oc_rotvec.decide(robot_state).satisfied);

// more extensive testing using the test data hardcoded at the top of this file
Expand Down Expand Up @@ -457,20 +457,20 @@ TEST_F(FloatingJointRobot, OrientationConstraintsParameterization)
robot_state.update();

ocm.parameterization = moveit_msgs::msg::OrientationConstraint::XYZ_EULER_ANGLES;
ocm.orientation = tf2::toMsg(xyz_intrinsix_to_quat(0.1, 0.2, -0.3));
ocm.orientation = tf2::toMsg(xyzIntrinsixToQuaternion(0.1, 0.2, -0.3));
EXPECT_TRUE(oc_euler.configure(ocm, tf));
EXPECT_TRUE(oc_euler.decide(robot_state).satisfied);

ocm.orientation = tf2::toMsg(xyz_intrinsix_to_quat(0.1, 0.2, -0.6));
ocm.orientation = tf2::toMsg(xyzIntrinsixToQuaternion(0.1, 0.2, -0.6));
EXPECT_TRUE(oc_euler.configure(ocm, tf));
EXPECT_FALSE(oc_euler.decide(robot_state).satisfied);

ocm.parameterization = moveit_msgs::msg::OrientationConstraint::ROTATION_VECTOR;
ocm.orientation = tf2::toMsg(rotation_vector_to_quat(0.1, 0.2, -0.3));
ocm.orientation = tf2::toMsg(rotationVectorToQuaternion(0.1, 0.2, -0.3));
EXPECT_TRUE(oc_rotvec.configure(ocm, tf));
EXPECT_TRUE(oc_rotvec.decide(robot_state).satisfied);

ocm.orientation = tf2::toMsg(rotation_vector_to_quat(0.1, 0.2, -0.6));
ocm.orientation = tf2::toMsg(rotationVectorToQuaternion(0.1, 0.2, -0.6));
EXPECT_TRUE(oc_rotvec.configure(ocm, tf));
EXPECT_FALSE(oc_rotvec.decide(robot_state).satisfied);
}
Expand Down
6 changes: 3 additions & 3 deletions moveit_core/planning_interface/src/planning_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,10 +53,10 @@ struct ActiveContexts
std::set<PlanningContext*> contexts_;
};

static ActiveContexts& getActiveContexts()
ActiveContexts& getActiveContexts()
{
static ActiveContexts ac;
return ac;
static ActiveContexts s_ac;
return s_ac;
}
} // namespace

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ bool callAdapter(const PlanningRequestAdapter& adapter, const PlanningRequestAda
std::swap(res.added_path_index, added_path_index);
bool result = adapter.adaptAndPlan(planner, planning_scene, req, res);
std::swap(res.added_path_index, added_path_index);
RCLCPP_DEBUG_STREAM(LOGGER, adapter.getDescription() << ": " << moveit::core::error_code_to_string(res.error_code));
RCLCPP_DEBUG_STREAM(LOGGER, adapter.getDescription() << ": " << moveit::core::errorCodeToString(res.error_code));
return result;
}
catch (std::exception& ex)
Expand Down
Loading