diff --git a/moveit_planners/pilz_industrial_motion_planner/include/joint_limits/joint_limits.hpp b/moveit_planners/pilz_industrial_motion_planner/include/joint_limits/joint_limits.hpp index 445dbf9ab1b..8ebfe2f4b59 100644 --- a/moveit_planners/pilz_industrial_motion_planner/include/joint_limits/joint_limits.hpp +++ b/moveit_planners/pilz_industrial_motion_planner/include/joint_limits/joint_limits.hpp @@ -59,7 +59,7 @@ struct JointLimits bool has_effort_limits; bool angle_wraparound; - std::string to_string() + std::string to_string() // NOLINT: Ignore case style { std::stringstream ss_output; @@ -96,7 +96,7 @@ struct JointLimits return ss_output.str(); } - std::string debug_to_string() + std::string debug_to_string() // NOLINT: Ignore case style { std::stringstream ss_output; diff --git a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_joint_limits_aggregator.cpp b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_joint_limits_aggregator.cpp index 4c42f72d5bd..e037f308ee6 100644 --- a/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_joint_limits_aggregator.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/test/unit_tests/src/unittest_joint_limits_aggregator.cpp @@ -142,7 +142,7 @@ TEST_F(JointLimitsAggregator, CorrectSettingAccelerationAndDeceleration) pilz_industrial_motion_planner::JointLimitsAggregator::getAggregatedLimits(node_, "all_valid", robot_model_->getActiveJointModels()); - for (std::pair lim : container) + for (const std::pair& lim : container) { if (lim.first == "prbt_joint_4") {