Skip to content

Commit 94fea79

Browse files
authored
Update clang-format-14 with QualifierAlignment (#2362)
* Set qualifier order in .clang-format * Ran pre-commit to update according to new style guide
1 parent 459b810 commit 94fea79

File tree

31 files changed

+60
-56
lines changed

31 files changed

+60
-56
lines changed

.clang-format

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -59,6 +59,10 @@ SpaceBeforeAssignmentOperators: true
5959
# Configure each individual brace in BraceWrapping
6060
BreakBeforeBraces: Custom
6161

62+
# Qualifiers (const, volatile, static, etc)
63+
QualifierAlignment: Custom
64+
QualifierOrder: ['static', 'inline', 'constexpr', 'const', 'volatile', 'type']
65+
6266
# Control of individual brace wrapping cases
6367
BraceWrapping:
6468
AfterCaseLabel: true

moveit_core/collision_detection/src/collision_matrix.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -64,10 +64,10 @@ AllowedCollisionMatrix::AllowedCollisionMatrix(const srdf::Model& srdf)
6464
for (const std::string& name : srdf.getNoDefaultCollisionLinks())
6565
setDefaultEntry(name, collision_detection::AllowedCollision::ALWAYS);
6666
// re-enable specific collision pairs
67-
for (auto const& collision : srdf.getEnabledCollisionPairs())
67+
for (const auto& collision : srdf.getEnabledCollisionPairs())
6868
setEntry(collision.link1_, collision.link2_, false);
6969
// *finally* disable selected collision pairs
70-
for (auto const& collision : srdf.getDisabledCollisionPairs())
70+
for (const auto& collision : srdf.getDisabledCollisionPairs())
7171
setEntry(collision.link1_, collision.link2_, true);
7272
}
7373

moveit_core/collision_distance_field/src/collision_distance_field_types.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -43,7 +43,7 @@
4343
#include <rclcpp/time.hpp>
4444
#include <memory>
4545

46-
const static double EPSILON{ 0.0001 };
46+
static const double EPSILON{ 0.0001 };
4747

4848
namespace collision_detection
4949
{

moveit_core/kinematics_base/include/moveit/kinematics_base/kinematics_base.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -156,7 +156,7 @@ class MOVEIT_KINEMATICS_BASE_EXPORT KinematicsBase
156156

157157
/** @brief Signature for a cost function used to evaluate IK solutions. */
158158
using IKCostFn = std::function<double(const geometry_msgs::msg::Pose&, const moveit::core::RobotState&,
159-
moveit::core::JointModelGroup const*, const std::vector<double>&)>;
159+
const moveit::core::JointModelGroup*, const std::vector<double>&)>;
160160

161161
/**
162162
* @brief Given a desired pose of the end-effector, compute the joint angles to reach it

moveit_core/robot_trajectory/include/moveit/robot_trajectory/robot_trajectory.h

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -398,18 +398,18 @@ std::ostream& operator<<(std::ostream& out, const RobotTrajectory& trajectory);
398398
/// active joint distances between the two states (L1 norm).
399399
/// \param[in] trajectory Given robot trajectory
400400
/// \return Length of the robot trajectory [rad]
401-
[[nodiscard]] double path_length(RobotTrajectory const& trajectory);
401+
[[nodiscard]] double path_length(const RobotTrajectory& trajectory);
402402

403403
/// \brief Calculate the smoothness of a given trajectory
404404
/// \param[in] trajectory Given robot trajectory
405405
/// \return Smoothness of the given trajectory
406406
/// or nullopt if it is not possible to calculate the smoothness
407-
[[nodiscard]] std::optional<double> smoothness(RobotTrajectory const& trajectory);
407+
[[nodiscard]] std::optional<double> smoothness(const RobotTrajectory& trajectory);
408408

409409
/// \brief Calculate the waypoint density of a trajectory
410410
/// \param[in] trajectory Given robot trajectory
411411
/// \return Waypoint density of the given trajectory
412412
/// or nullopt if it is not possible to calculate the density
413-
[[nodiscard]] std::optional<double> waypoint_density(RobotTrajectory const& trajectory);
413+
[[nodiscard]] std::optional<double> waypoint_density(const RobotTrajectory& trajectory);
414414

415415
} // namespace robot_trajectory

moveit_core/robot_trajectory/src/robot_trajectory.cpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -636,19 +636,19 @@ std::ostream& operator<<(std::ostream& out, const RobotTrajectory& trajectory)
636636
return out;
637637
}
638638

639-
double path_length(RobotTrajectory const& trajectory)
639+
double path_length(const RobotTrajectory& trajectory)
640640
{
641641
auto trajectory_length = 0.0;
642642
for (std::size_t index = 1; index < trajectory.getWayPointCount(); ++index)
643643
{
644-
auto const& first = trajectory.getWayPoint(index - 1);
645-
auto const& second = trajectory.getWayPoint(index);
644+
const auto& first = trajectory.getWayPoint(index - 1);
645+
const auto& second = trajectory.getWayPoint(index);
646646
trajectory_length += first.distance(second);
647647
}
648648
return trajectory_length;
649649
}
650650

651-
std::optional<double> smoothness(RobotTrajectory const& trajectory)
651+
std::optional<double> smoothness(const RobotTrajectory& trajectory)
652652
{
653653
if (trajectory.getWayPointCount() > 2)
654654
{
@@ -686,13 +686,13 @@ std::optional<double> smoothness(RobotTrajectory const& trajectory)
686686
return std::nullopt;
687687
}
688688

689-
std::optional<double> waypoint_density(RobotTrajectory const& trajectory)
689+
std::optional<double> waypoint_density(const RobotTrajectory& trajectory)
690690
{
691691
// Only calculate density if more than one waypoint exists
692692
if (trajectory.getWayPointCount() > 1)
693693
{
694694
// Calculate path length
695-
auto const length = path_length(trajectory);
695+
const auto length = path_length(trajectory);
696696
if (length > 0.0)
697697
{
698698
auto density = static_cast<double>(trajectory.getWayPointCount()) / length;

moveit_core/trajectory_processing/include/moveit/trajectory_processing/ruckig_traj_smoothing.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -108,7 +108,7 @@ class RuckigSmoothing
108108
*/
109109
[[nodiscard]] static bool getRobotModelBounds(const double max_velocity_scaling_factor,
110110
const double max_acceleration_scaling_factor,
111-
moveit::core::JointModelGroup const* const group,
111+
const moveit::core::JointModelGroup* const group,
112112
ruckig::InputParameter<ruckig::DynamicDOFs>& ruckig_input);
113113

114114
/**

moveit_core/trajectory_processing/src/ruckig_traj_smoothing.cpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -75,7 +75,7 @@ bool RuckigSmoothing::applySmoothing(robot_trajectory::RobotTrajectory& trajecto
7575
}
7676

7777
// Kinematic limits (vels/accels/jerks) from RobotModel
78-
moveit::core::JointModelGroup const* const group = trajectory.getGroup();
78+
const moveit::core::JointModelGroup* const group = trajectory.getGroup();
7979
const size_t num_dof = group->getVariableCount();
8080
ruckig::InputParameter<ruckig::DynamicDOFs> ruckig_input{ num_dof };
8181
if (!getRobotModelBounds(max_velocity_scaling_factor, max_acceleration_scaling_factor, group, ruckig_input))
@@ -109,7 +109,7 @@ bool RuckigSmoothing::applySmoothing(robot_trajectory::RobotTrajectory& trajecto
109109
}
110110

111111
// Set default kinematic limits (vels/accels/jerks)
112-
moveit::core::JointModelGroup const* const group = trajectory.getGroup();
112+
const moveit::core::JointModelGroup* const group = trajectory.getGroup();
113113
const size_t num_dof = group->getVariableCount();
114114
ruckig::InputParameter<ruckig::DynamicDOFs> ruckig_input{ num_dof };
115115
if (!getRobotModelBounds(max_velocity_scaling_factor, max_acceleration_scaling_factor, group, ruckig_input))
@@ -176,7 +176,7 @@ bool RuckigSmoothing::applySmoothing(robot_trajectory::RobotTrajectory& trajecto
176176

177177
bool RuckigSmoothing::validateGroup(const robot_trajectory::RobotTrajectory& trajectory)
178178
{
179-
moveit::core::JointModelGroup const* const group = trajectory.getGroup();
179+
const moveit::core::JointModelGroup* const group = trajectory.getGroup();
180180
if (!group)
181181
{
182182
RCLCPP_ERROR(LOGGER, "The planner did not set the group the plan was computed for");
@@ -187,7 +187,7 @@ bool RuckigSmoothing::validateGroup(const robot_trajectory::RobotTrajectory& tra
187187

188188
bool RuckigSmoothing::getRobotModelBounds(const double max_velocity_scaling_factor,
189189
const double max_acceleration_scaling_factor,
190-
moveit::core::JointModelGroup const* const group,
190+
const moveit::core::JointModelGroup* const group,
191191
ruckig::InputParameter<ruckig::DynamicDOFs>& ruckig_input)
192192
{
193193
const size_t num_dof = group->getVariableCount();
@@ -244,7 +244,7 @@ bool RuckigSmoothing::runRuckig(robot_trajectory::RobotTrajectory& trajectory,
244244
const bool mitigate_overshoot, const double overshoot_threshold)
245245
{
246246
const size_t num_waypoints = trajectory.getWayPointCount();
247-
moveit::core::JointModelGroup const* const group = trajectory.getGroup();
247+
const moveit::core::JointModelGroup* const group = trajectory.getGroup();
248248
const size_t num_dof = group->getVariableCount();
249249
ruckig::OutputParameter<ruckig::DynamicDOFs> ruckig_output{ num_dof };
250250

moveit_core/trajectory_processing/test/test_ruckig_traj_smoothing.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -158,9 +158,9 @@ TEST_F(RuckigTests, single_waypoint)
158158
EXPECT_TRUE(
159159
smoother_.applySmoothing(*trajectory_, 1.0 /* max vel scaling factor */, 1.0 /* max accel scaling factor */));
160160
// And the waypoint did not change
161-
auto const new_first_waypoint = trajectory_->getFirstWayPointPtr();
162-
auto const& variable_names = new_first_waypoint->getVariableNames();
163-
for (std::string const& variable_name : variable_names)
161+
const auto new_first_waypoint = trajectory_->getFirstWayPointPtr();
162+
const auto& variable_names = new_first_waypoint->getVariableNames();
163+
for (const std::string& variable_name : variable_names)
164164
{
165165
EXPECT_EQ(first_waypoint_input.getVariablePosition(variable_name),
166166
new_first_waypoint->getVariablePosition(variable_name));

moveit_kinematics/test/test_kinematics_plugin.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -85,7 +85,7 @@ class SharedData
8585
int num_nearest_ik_tests_;
8686
bool publish_trajectory_;
8787

88-
SharedData(SharedData const&) = delete; // this is a singleton
88+
SharedData(const SharedData&) = delete; // this is a singleton
8989
SharedData()
9090
{
9191
initialize();

0 commit comments

Comments
 (0)