From 7d5f9fe6e39fe714c2c69fdd7a73d0d37f28a6c1 Mon Sep 17 00:00:00 2001 From: Robert Haschke Date: Wed, 2 Nov 2022 12:25:03 +0100 Subject: [PATCH] Fix clang-tidy warnings --- .../task_constructor/stages/fixed_state.h | 2 +- .../include/moveit/task_constructor/storage.h | 2 +- core/src/stage.cpp | 4 +-- core/src/stages/compute_ik.cpp | 2 +- core/src/stages/fixed_state.cpp | 2 +- core/test/test_move_relative.cpp | 8 +++--- core/test/test_move_to.cpp | 27 ++++++++++--------- core/test/test_stage.cpp | 2 +- .../motion_planning_tasks/src/task_panel.cpp | 2 +- 9 files changed, 26 insertions(+), 25 deletions(-) diff --git a/core/include/moveit/task_constructor/stages/fixed_state.h b/core/include/moveit/task_constructor/stages/fixed_state.h index 2ace2726..adb3bb1c 100644 --- a/core/include/moveit/task_constructor/stages/fixed_state.h +++ b/core/include/moveit/task_constructor/stages/fixed_state.h @@ -48,7 +48,7 @@ namespace stages { class FixedState : public Generator { public: - FixedState(const std::string& name = "initial state", planning_scene::PlanningScenePtr = nullptr); + FixedState(const std::string& name = "initial state", planning_scene::PlanningScenePtr scene = nullptr); void setState(const planning_scene::PlanningScenePtr& scene); void reset() override; diff --git a/core/include/moveit/task_constructor/storage.h b/core/include/moveit/task_constructor/storage.h index ed8ef9d2..c11bbd79 100644 --- a/core/include/moveit/task_constructor/storage.h +++ b/core/include/moveit/task_constructor/storage.h @@ -248,7 +248,7 @@ private: std::ostream& operator<<(std::ostream& os, const InterfaceState::Priority& prio); std::ostream& operator<<(std::ostream& os, const Interface& interface); -std::ostream& operator<<(std::ostream& os, Interface::Direction); +std::ostream& operator<<(std::ostream& os, Interface::Direction dir); /// Find index of the iterator in the container. Counting starts at 1. Zero corresponds to not found. template diff --git a/core/src/stage.cpp b/core/src/stage.cpp index 60315e57..6b2ff546 100644 --- a/core/src/stage.cpp +++ b/core/src/stage.cpp @@ -125,8 +125,8 @@ StagePrivate& StagePrivate::operator=(StagePrivate&& other) { prev_ends_ = std::move(other.prev_ends_); next_starts_ = std::move(other.next_starts_); - parent_ = std::move(other.parent_); - it_ = std::move(other.it_); + parent_ = other.parent_; + it_ = other.it_; other.unparent(); return *this; diff --git a/core/src/stages/compute_ik.cpp b/core/src/stages/compute_ik.cpp index 2b8ece2a..1f793f77 100644 --- a/core/src/stages/compute_ik.cpp +++ b/core/src/stages/compute_ik.cpp @@ -373,7 +373,7 @@ void ComputeIK::compute() { req.max_contacts = 1; scene->checkCollision(req, res, *state); solution.feasible = ignore_collisions || !res.collision; - if (res.contacts.size() > 0) { + if (!res.contacts.empty()) { solution.contact = res.contacts.begin()->second.front(); } return solution.feasible; diff --git a/core/src/stages/fixed_state.cpp b/core/src/stages/fixed_state.cpp index 9c4d99b0..0c8ebaad 100644 --- a/core/src/stages/fixed_state.cpp +++ b/core/src/stages/fixed_state.cpp @@ -44,7 +44,7 @@ namespace task_constructor { namespace stages { FixedState::FixedState(const std::string& name, planning_scene::PlanningScenePtr scene) - : Generator(name), scene_(scene) { + : Generator(name), scene_(std::move(scene)) { properties().declare("ignore_collisions", false); setCostTerm(std::make_unique(0.0)); } diff --git a/core/test/test_move_relative.cpp b/core/test/test_move_relative.cpp index 37c12705..43caa12f 100644 --- a/core/test/test_move_relative.cpp +++ b/core/test/test_move_relative.cpp @@ -113,9 +113,9 @@ TEST_F(PandaMoveRelative, cartesianCircular) { } TEST_F(PandaMoveRelative, cartesianRotateAttachedIKFrame) { - const std::string ATTACHED_OBJECT{ "attached_object" }; - scene->processAttachedCollisionObjectMsg(createAttachedObject(ATTACHED_OBJECT)); - move->setIKFrame(ATTACHED_OBJECT); + const std::string attached_object{ "attached_object" }; + scene->processAttachedCollisionObjectMsg(createAttachedObject(attached_object)); + move->setIKFrame(attached_object); move->setDirection([] { geometry_msgs::TwistStamped twist; @@ -125,7 +125,7 @@ TEST_F(PandaMoveRelative, cartesianRotateAttachedIKFrame) { }()); ASSERT_TRUE(t.plan()) << "Failed to plan"; - EXPECT_CONST_POSITION(move->solutions().front(), ATTACHED_OBJECT); + EXPECT_CONST_POSITION(move->solutions().front(), attached_object); } int main(int argc, char** argv) { diff --git a/core/test/test_move_to.cpp b/core/test/test_move_to.cpp index 83d6b076..8e7ac023 100644 --- a/core/test/test_move_to.cpp +++ b/core/test/test_move_to.cpp @@ -72,7 +72,8 @@ TEST_F(PandaMoveTo, stateTarget) { EXPECT_ONE_SOLUTION; } -geometry_msgs::PoseStamped getFramePoseOfNamedState(RobotState state, std::string pose, std::string frame) { +geometry_msgs::PoseStamped getFramePoseOfNamedState(RobotState state, const std::string& pose, + const std::string& frame) { state.setToDefaultValues(state.getRobotModel()->getJointModelGroup("panda_arm"), pose); auto frame_eigen{ state.getFrameTransform(frame) }; geometry_msgs::PoseStamped p; @@ -98,9 +99,9 @@ TEST_F(PandaMoveTo, poseTarget) { } TEST_F(PandaMoveTo, poseIKFrameLinkTarget) { - const std::string IK_FRAME{ "panda_hand" }; - move_to->setIKFrame(IK_FRAME); - move_to->setGoal(getFramePoseOfNamedState(scene->getCurrentState(), "ready", IK_FRAME)); + const std::string ik_frame{ "panda_hand" }; + move_to->setIKFrame(ik_frame); + move_to->setGoal(getFramePoseOfNamedState(scene->getCurrentState(), "ready", ik_frame)); EXPECT_ONE_SOLUTION; } @@ -129,22 +130,22 @@ moveit_msgs::AttachedCollisionObject createAttachedObject(const std::string& id) } TEST_F(PandaMoveTo, poseIKFrameAttachedTarget) { - const std::string ATTACHED_OBJECT{ "attached_object" }; - scene->processAttachedCollisionObjectMsg(createAttachedObject(ATTACHED_OBJECT)); + const std::string attached_object{ "attached_object" }; + scene->processAttachedCollisionObjectMsg(createAttachedObject(attached_object)); - move_to->setIKFrame(ATTACHED_OBJECT); - move_to->setGoal(getFramePoseOfNamedState(scene->getCurrentState(), "ready", ATTACHED_OBJECT)); + move_to->setIKFrame(attached_object); + move_to->setGoal(getFramePoseOfNamedState(scene->getCurrentState(), "ready", attached_object)); EXPECT_ONE_SOLUTION; } TEST_F(PandaMoveTo, poseIKFrameAttachedSubframeTarget) { - const std::string ATTACHED_OBJECT{ "attached_object" }; - const std::string IK_FRAME{ ATTACHED_OBJECT + "/subframe" }; + const std::string attached_object{ "attached_object" }; + const std::string ik_frame{ attached_object + "/subframe" }; - scene->processAttachedCollisionObjectMsg(createAttachedObject(ATTACHED_OBJECT)); + scene->processAttachedCollisionObjectMsg(createAttachedObject(attached_object)); - move_to->setIKFrame(IK_FRAME); - move_to->setGoal(getFramePoseOfNamedState(scene->getCurrentState(), "ready", IK_FRAME)); + move_to->setIKFrame(ik_frame); + move_to->setGoal(getFramePoseOfNamedState(scene->getCurrentState(), "ready", ik_frame)); EXPECT_ONE_SOLUTION; } diff --git a/core/test/test_stage.cpp b/core/test/test_stage.cpp index 180bc70d..01284a96 100644 --- a/core/test/test_stage.cpp +++ b/core/test/test_stage.cpp @@ -19,7 +19,7 @@ struct StandaloneGeneratorMockup : public GeneratorMockup InterfacePtr next; StandaloneGeneratorMockup(std::initializer_list&& costs) - : StandaloneGeneratorMockup{ PredefinedCosts{ std::move(costs), true } } {} + : StandaloneGeneratorMockup{ PredefinedCosts{ costs, true } } {} StandaloneGeneratorMockup(PredefinedCosts&& costs = PredefinedCosts{ { 0.0 }, true }) : GeneratorMockup{ std::move(costs) } { diff --git a/visualization/motion_planning_tasks/src/task_panel.cpp b/visualization/motion_planning_tasks/src/task_panel.cpp index b73e2e15..f571ccb0 100644 --- a/visualization/motion_planning_tasks/src/task_panel.cpp +++ b/visualization/motion_planning_tasks/src/task_panel.cpp @@ -172,7 +172,7 @@ TaskPanelPrivate::TaskPanelPrivate(TaskPanel* panel) : q_ptr(panel) { tool_buttons_group = new QButtonGroup(panel); tool_buttons_group->setExclusive(true); button_show_stage_dock_widget->setEnabled(bool(getStageFactory())); - button_show_stage_dock_widget->setToolTip(QStringLiteral("Show available stages")); + button_show_stage_dock_widget->setToolTip("Show available stages"); property_root = new rviz::Property("Global Settings"); }