From 28b3e24a26b2b2df24ffd05cc3f77150557d3fb9 Mon Sep 17 00:00:00 2001 From: Robert Haschke Date: Sat, 21 Dec 2024 17:41:29 +0100 Subject: [PATCH 1/6] CI: Drop obsolete clang-tidy option AnalyzeTemporaryDtors --- .clang-tidy | 1 - 1 file changed, 1 deletion(-) diff --git a/.clang-tidy b/.clang-tidy index 181fbf69c..ed398ab43 100644 --- a/.clang-tidy +++ b/.clang-tidy @@ -17,7 +17,6 @@ Checks: 'performance-*, readability-identifier-naming, ' HeaderFilterRegex: '.*/moveit/task_constructor/.*\.h' -AnalyzeTemporaryDtors: false CheckOptions: - key: llvm-namespace-comment.ShortNamespaceLines value: '10' From 5067dbb43213c508ef4a34bd5ad761b1e518b647 Mon Sep 17 00:00:00 2001 From: Robert Haschke Date: Sun, 22 Dec 2024 12:28:26 +0100 Subject: [PATCH 2/6] clang-tidy fixes --- .../moveit/task_constructor/solvers/cartesian_path.h | 2 +- .../moveit/task_constructor/stages/generate_random_pose.h | 2 +- core/python/bindings/src/properties.cpp | 2 +- core/test/stage_mockups.h | 8 ++++---- 4 files changed, 7 insertions(+), 7 deletions(-) diff --git a/core/include/moveit/task_constructor/solvers/cartesian_path.h b/core/include/moveit/task_constructor/solvers/cartesian_path.h index 8de351da8..4214f09c0 100644 --- a/core/include/moveit/task_constructor/solvers/cartesian_path.h +++ b/core/include/moveit/task_constructor/solvers/cartesian_path.h @@ -60,7 +60,7 @@ class CartesianPath : public PlannerInterface void setStepSize(double step_size) { setProperty("step_size", step_size); } void setPrecision(const moveit::core::CartesianPrecision& precision) { setProperty("precision", precision); } template - void setJumpThreshold(double) { + void setJumpThreshold(double /*unused*/) { static_assert(std::is_integral::value, "setJumpThreshold() is deprecated. Replace with setPrecision."); } void setMinFraction(double min_fraction) { setProperty("min_fraction", min_fraction); } diff --git a/core/include/moveit/task_constructor/stages/generate_random_pose.h b/core/include/moveit/task_constructor/stages/generate_random_pose.h index 86eb0bbf9..139a5f4f5 100644 --- a/core/include/moveit/task_constructor/stages/generate_random_pose.h +++ b/core/include/moveit/task_constructor/stages/generate_random_pose.h @@ -56,7 +56,7 @@ class GenerateRandomPose : public GeneratePose /** Function signature for pose dimension samplers. * The input parameter is the seed, the returned value is the sampling result. */ - typedef std::function PoseDimensionSampler; + using PoseDimensionSampler = std::function; enum PoseDimension { X, diff --git a/core/python/bindings/src/properties.cpp b/core/python/bindings/src/properties.cpp index 142ec3e74..5191fabb1 100644 --- a/core/python/bindings/src/properties.cpp +++ b/core/python/bindings/src/properties.cpp @@ -59,7 +59,7 @@ class PropertyConverterRegistry PropertyConverterBase::from_python_converter_function from_; }; // map from type_index to corresponding converter functions - typedef std::map RegistryMap; + using RegistryMap = std::map; RegistryMap types_; // map from ros-msg-names to entry in types_ using RosMsgTypeNameMap = std::map; diff --git a/core/test/stage_mockups.h b/core/test/stage_mockups.h index 35d01e659..25d47a054 100644 --- a/core/test/stage_mockups.h +++ b/core/test/stage_mockups.h @@ -65,7 +65,7 @@ struct GeneratorMockup : public Generator void init(const moveit::core::RobotModelConstPtr& robot_model) override; bool canCompute() const override; void compute() override; - virtual void reset() override { runs_ = 0; }; + void reset() override { runs_ = 0; }; }; struct MonitoringGeneratorMockup : public MonitoringGenerator @@ -82,7 +82,7 @@ struct MonitoringGeneratorMockup : public MonitoringGenerator bool canCompute() const override { return false; } void compute() override {} void onNewSolution(const SolutionBase& s) override; - virtual void reset() override { runs_ = 0; }; + void reset() override { runs_ = 0; }; }; struct ConnectMockup : public Connecting @@ -99,7 +99,7 @@ struct ConnectMockup : public Connecting using Connecting::compatible; // make this accessible for testing void compute(const InterfaceState& from, const InterfaceState& to) override; - virtual void reset() override { runs_ = 0; }; + void reset() override { runs_ = 0; }; }; struct PropagatorMockup : public PropagatingEitherWay @@ -116,7 +116,7 @@ struct PropagatorMockup : public PropagatingEitherWay void computeForward(const InterfaceState& from) override; void computeBackward(const InterfaceState& to) override; - virtual void reset() override { runs_ = 0; }; + void reset() override { runs_ = 0; }; }; struct ForwardMockup : public PropagatorMockup From 45ea86c163adf678a187ff5cb3a854a7dba8c36e Mon Sep 17 00:00:00 2001 From: Robert Haschke Date: Sun, 22 Dec 2024 12:28:46 +0100 Subject: [PATCH 3/6] clang-tidy fixes: use uint8_t enums --- core/include/moveit/task_constructor/cost_terms.h | 2 +- core/include/moveit/task_constructor/stage.h | 6 +++--- core/include/moveit/task_constructor/stages/connect.h | 2 +- .../moveit/task_constructor/stages/generate_random_pose.h | 2 +- core/include/moveit/task_constructor/storage.h | 6 +++--- core/test/test_container.cpp | 2 +- .../include/rviz_marker_tools/marker_creation.h | 2 +- .../motion_planning_tasks/src/remote_task_model.cpp | 2 +- visualization/motion_planning_tasks/src/task_list_model.h | 2 +- visualization/motion_planning_tasks/src/task_panel.h | 4 ++-- visualization/motion_planning_tasks/utils/icon.h | 2 +- 11 files changed, 16 insertions(+), 16 deletions(-) diff --git a/core/include/moveit/task_constructor/cost_terms.h b/core/include/moveit/task_constructor/cost_terms.h index 353464081..3beb8db91 100644 --- a/core/include/moveit/task_constructor/cost_terms.h +++ b/core/include/moveit/task_constructor/cost_terms.h @@ -70,7 +70,7 @@ class CostTerm class TrajectoryCostTerm : public CostTerm { public: - enum class Mode + enum class Mode : uint8_t { AUTO /* TRAJECTORY, or START_INTERFACE if no trajectory is given */, START_INTERFACE, diff --git a/core/include/moveit/task_constructor/stage.h b/core/include/moveit/task_constructor/stage.h index 74fb3941e..37be554a6 100644 --- a/core/include/moveit/task_constructor/stage.h +++ b/core/include/moveit/task_constructor/stage.h @@ -72,7 +72,7 @@ MOVEIT_CLASS_FORWARD(RobotTrajectory); namespace moveit { namespace task_constructor { -enum InterfaceFlag +enum InterfaceFlag : uint8_t { READS_START = 0x01, READS_END = 0x02, @@ -155,7 +155,7 @@ class Stage * * INTERFACE takes precedence over PARENT. */ - enum PropertyInitializerSource + enum PropertyInitializerSource : uint8_t { // TODO: move to property.cpp DEFAULT = 0, MANUAL = 1, @@ -293,7 +293,7 @@ class PropagatingEitherWay : public ComputeBase PRIVATE_CLASS(PropagatingEitherWay) PropagatingEitherWay(const std::string& name = "propagating either way"); - enum Direction + enum Direction : uint8_t { AUTO = 0x00, // auto-derive direction from context FORWARD = 0x01, // propagate forward only diff --git a/core/include/moveit/task_constructor/stages/connect.h b/core/include/moveit/task_constructor/stages/connect.h index bac878fd9..c4aba253b 100644 --- a/core/include/moveit/task_constructor/stages/connect.h +++ b/core/include/moveit/task_constructor/stages/connect.h @@ -67,7 +67,7 @@ class Connect : public Connecting bool compatible(const InterfaceState& from_state, const InterfaceState& to_state) const override; public: - enum MergeMode + enum MergeMode : uint8_t { SEQUENTIAL = 0, WAYPOINTS = 1 diff --git a/core/include/moveit/task_constructor/stages/generate_random_pose.h b/core/include/moveit/task_constructor/stages/generate_random_pose.h index 139a5f4f5..c6643daff 100644 --- a/core/include/moveit/task_constructor/stages/generate_random_pose.h +++ b/core/include/moveit/task_constructor/stages/generate_random_pose.h @@ -57,7 +57,7 @@ class GenerateRandomPose : public GeneratePose /** Function signature for pose dimension samplers. * The input parameter is the seed, the returned value is the sampling result. */ using PoseDimensionSampler = std::function; - enum PoseDimension + enum PoseDimension : uint8_t { X, Y, diff --git a/core/include/moveit/task_constructor/storage.h b/core/include/moveit/task_constructor/storage.h index e0796980d..c1059d332 100644 --- a/core/include/moveit/task_constructor/storage.h +++ b/core/include/moveit/task_constructor/storage.h @@ -80,7 +80,7 @@ class InterfaceState friend class ContainerBasePrivate; // allow setting priority_ for pruning public: - enum Status + enum Status : uint8_t { ENABLED, // state is actively considered during planning ARMED, // disabled state in a Connecting interface that will become re-enabled with a new opposite state @@ -197,12 +197,12 @@ class Interface : public ordered const InterfaceState* operator->() const noexcept { return base_type::const_iterator::operator*(); } }; - enum Direction + enum Direction : uint8_t { FORWARD, BACKWARD, }; - enum Update + enum Update : uint8_t { STATUS = 1 << 0, PRIORITY = 1 << 1, diff --git a/core/test/test_container.cpp b/core/test/test_container.cpp index 5d7b722c9..670ffef69 100644 --- a/core/test/test_container.cpp +++ b/core/test/test_container.cpp @@ -15,7 +15,7 @@ using namespace moveit::task_constructor; -enum StageType +enum StageType : uint8_t { GEN, FW, diff --git a/rviz_marker_tools/include/rviz_marker_tools/marker_creation.h b/rviz_marker_tools/include/rviz_marker_tools/marker_creation.h index 222456bde..7e0c5c971 100644 --- a/rviz_marker_tools/include/rviz_marker_tools/marker_creation.h +++ b/rviz_marker_tools/include/rviz_marker_tools/marker_creation.h @@ -11,7 +11,7 @@ class Geometry; namespace rviz_marker_tools { -enum Color +enum Color : uint8_t { BLACK = 0, BROWN = 1, diff --git a/visualization/motion_planning_tasks/src/remote_task_model.cpp b/visualization/motion_planning_tasks/src/remote_task_model.cpp index 430a31578..6d5ecc57d 100644 --- a/visualization/motion_planning_tasks/src/remote_task_model.cpp +++ b/visualization/motion_planning_tasks/src/remote_task_model.cpp @@ -54,7 +54,7 @@ using namespace moveit::task_constructor; namespace moveit_rviz_plugin { -enum NodeFlag +enum NodeFlag : uint8_t { WAS_VISITED = 0x01, // indicate that model should emit change notifications NAME_CHANGED = 0x02, // indicate that name was manually changed diff --git a/visualization/motion_planning_tasks/src/task_list_model.h b/visualization/motion_planning_tasks/src/task_list_model.h index 0386543d2..c82eb06fa 100644 --- a/visualization/motion_planning_tasks/src/task_list_model.h +++ b/visualization/motion_planning_tasks/src/task_list_model.h @@ -77,7 +77,7 @@ class BaseTaskModel : public QAbstractItemModel rviz::DisplayContext* display_context_; public: - enum TaskModelFlag + enum TaskModelFlag : uint8_t { LOCAL_MODEL = 0x01, IS_DESTROYED = 0x02, diff --git a/visualization/motion_planning_tasks/src/task_panel.h b/visualization/motion_planning_tasks/src/task_panel.h index e372731fe..58fe9a23e 100644 --- a/visualization/motion_planning_tasks/src/task_panel.h +++ b/visualization/motion_planning_tasks/src/task_panel.h @@ -118,7 +118,7 @@ class TaskView : public SubPanel protected: // configuration settings - enum TaskExpand + enum TaskExpand : uint8_t { EXPAND_TOP = 1, EXPAND_ALL, @@ -130,7 +130,7 @@ class TaskView : public SubPanel rviz::BoolProperty* show_time_column; public: - enum OldTaskHandling + enum OldTaskHandling : uint8_t { OLD_TASK_KEEP = 1, OLD_TASK_REPLACE, diff --git a/visualization/motion_planning_tasks/utils/icon.h b/visualization/motion_planning_tasks/utils/icon.h index 630a43a36..7f709ff55 100644 --- a/visualization/motion_planning_tasks/utils/icon.h +++ b/visualization/motion_planning_tasks/utils/icon.h @@ -43,7 +43,7 @@ using IconMaskAndColor = QPair; class Icon : public QVector { public: - enum IconStyleOption + enum IconStyleOption : uint8_t { NONE = 0, TINT = 1, From 8c0609a7115bbeb18645d9ac8d13a79be986218d Mon Sep 17 00:00:00 2001 From: Robert Haschke Date: Sat, 21 Dec 2024 22:40:04 +0100 Subject: [PATCH 4/6] clang-tidy fixes: std::endl -> '\n' --- core/src/container.cpp | 14 +++++++------- core/src/introspection.cpp | 2 +- core/src/stage.cpp | 8 ++++---- core/test/pick_pa10.cpp | 2 +- core/test/pick_pr2.cpp | 2 +- core/test/pick_ur5.cpp | 2 +- core/test/test_container.cpp | 2 +- core/test/test_cost_queue.cpp | 2 +- core/test/test_move_to.cpp | 2 +- demo/src/alternative_path_costs.cpp | 2 +- demo/src/cartesian.cpp | 2 +- demo/src/fallbacks_move_to.cpp | 2 +- demo/src/ik_clearance_cost.cpp | 2 +- demo/src/modular.cpp | 2 +- 14 files changed, 23 insertions(+), 23 deletions(-) diff --git a/core/src/container.cpp b/core/src/container.cpp index 9d8197515..3fe6f1b5f 100644 --- a/core/src/container.cpp +++ b/core/src/container.cpp @@ -62,24 +62,24 @@ printChildrenInterfaces(const ContainerBasePrivate& container, bool success, con std::ostream& os = std::cerr) { static unsigned int id = 0; const unsigned int width = 10; // indentation of name - os << std::endl << (success ? '+' : '-') << ' ' << creator.name() << ' '; + os << '\n' << (success ? '+' : '-') << ' ' << creator.name() << ' '; if (success) os << ++id << ' '; if (const auto conn = dynamic_cast(creator.pimpl())) os << conn->pendingPairsPrinter(); - os << std::endl; + os << '\n'; for (const auto& child : container.children()) { auto cimpl = child->pimpl(); os << std::setw(width) << std::left << child->name(); if (!cimpl->starts() && !cimpl->ends()) - os << "↕ " << std::endl; + os << "↕ \n"; if (cimpl->starts()) - os << "↓ " << *child->pimpl()->starts() << std::endl; + os << "↓ " << *child->pimpl()->starts() << '\n'; if (cimpl->starts() && cimpl->ends()) os << std::setw(width) << " "; if (cimpl->ends()) - os << "↑ " << *child->pimpl()->ends() << std::endl; + os << "↑ " << *child->pimpl()->ends() << '\n'; } } @@ -459,7 +459,7 @@ void ContainerBase::explainFailure(std::ostream& os) const { if (stage->numFailures()) { os << stage->name() << " (0/" << stage->numFailures() << ")"; stage->explainFailure(os); - os << std::endl; + os << '\n'; break; } stage->explainFailure(os); // recursively process children @@ -468,7 +468,7 @@ void ContainerBase::explainFailure(std::ostream& os) const { std::ostream& operator<<(std::ostream& os, const ContainerBase& container) { ContainerBase::StageCallback processor = [&os](const Stage& stage, unsigned int depth) -> bool { - os << std::string(2 * depth, ' ') << *stage.pimpl() << std::endl; + os << std::string(2 * depth, ' ') << *stage.pimpl() << '\n'; return true; }; container.traverseRecursively(processor); diff --git a/core/src/introspection.cpp b/core/src/introspection.cpp index d46542e1a..535af345a 100644 --- a/core/src/introspection.cpp +++ b/core/src/introspection.cpp @@ -171,7 +171,7 @@ void Introspection::publishAllSolutions(bool wait) { publishSolution(*solution); if (wait) { - std::cout << "Press to continue ..." << std::endl; + std::cout << "Press to continue ...\n"; int ch = getchar(); if (ch == 'q' || ch == 'Q') break; diff --git a/core/src/stage.cpp b/core/src/stage.cpp index 896668e13..ec72c3d66 100644 --- a/core/src/stage.cpp +++ b/core/src/stage.cpp @@ -90,9 +90,9 @@ const char* InitStageException::what() const noexcept { } std::ostream& operator<<(std::ostream& os, const InitStageException& e) { - os << "Error initializing stage" << (e.errors_.size() > 1 ? "s" : "") << ":" << std::endl; + os << "Error initializing stage" << (e.errors_.size() > 1 ? "s" : "") << ":\n "; for (const auto& pair : e.errors_) - os << pair.first->name() << ": " << pair.second << std::endl; + os << pair.first->name() << ": " << pair.second << '\n'; return os; } @@ -840,10 +840,10 @@ void ConnectingPrivate::newState(Interface::iterator it, Interface::UpdateFlags os << (updated ? " !" : " +"); else os << " "; - os << d << " " << this->pullInterface(d) << ": " << *this->pullInterface(d) << std::endl; + os << d << " " << this->pullInterface(d) << ": " << *this->pullInterface(d) << '\n'; } os << std::setw(15) << " "; - os << pendingPairsPrinter() << std::endl; + os << pendingPairsPrinter() << '\n'; #endif } diff --git a/core/test/pick_pa10.cpp b/core/test/pick_pa10.cpp index 0751471a4..4bc8be51b 100644 --- a/core/test/pick_pa10.cpp +++ b/core/test/pick_pa10.cpp @@ -179,7 +179,7 @@ TEST(PA10, pick) { try { t.plan(); } catch (const InitStageException& e) { - ADD_FAILURE() << "planning failed with exception" << std::endl << e << t; + ADD_FAILURE() << "planning failed with exception\n" << e << t; } auto solutions = t.solutions().size(); diff --git a/core/test/pick_pr2.cpp b/core/test/pick_pr2.cpp index ac1706320..386fb3bfa 100644 --- a/core/test/pick_pr2.cpp +++ b/core/test/pick_pr2.cpp @@ -77,7 +77,7 @@ TEST(PR2, pick) { spawnObject(); t.plan(); } catch (const InitStageException& e) { - ADD_FAILURE() << "planning failed with exception" << std::endl << e << t; + ADD_FAILURE() << "planning failed with exception\n" << e << t; } auto solutions = t.solutions().size(); diff --git a/core/test/pick_ur5.cpp b/core/test/pick_ur5.cpp index 6c2808ec8..61912fc46 100644 --- a/core/test/pick_ur5.cpp +++ b/core/test/pick_ur5.cpp @@ -79,7 +79,7 @@ TEST(UR5, pick) { spawnObject(); t.plan(); } catch (const InitStageException& e) { - ADD_FAILURE() << "planning failed with exception" << std::endl << e << t; + ADD_FAILURE() << "planning failed with exception\n" << e << t; } auto solutions = t.solutions().size(); diff --git a/core/test/test_container.cpp b/core/test/test_container.cpp index 670ffef69..0bbd5e29f 100644 --- a/core/test/test_container.cpp +++ b/core/test/test_container.cpp @@ -625,7 +625,7 @@ TEST(Task, reuse) { configure(t); EXPECT_TRUE(t.plan(1)); } catch (const InitStageException& e) { - ADD_FAILURE() << "InitStageException:" << std::endl << e << t; + ADD_FAILURE() << "InitStageException:\n" << e << t; } } diff --git a/core/test/test_cost_queue.cpp b/core/test/test_cost_queue.cpp index 4aba46daa..3204ee3d1 100644 --- a/core/test/test_cost_queue.cpp +++ b/core/test/test_cost_queue.cpp @@ -126,7 +126,7 @@ TYPED_TEST(OrderedTest, sorting) { template std::ostream& operator<<(std::ostream& os, const cost_ordered& queue) { for (const auto& pair : queue.sorted()) - os << pair.cost() << ": " << pair.value() << std::endl; + os << pair.cost() << ": " << pair.value() << '\n'; return os; } diff --git a/core/test/test_move_to.cpp b/core/test/test_move_to.cpp index aaaf313eb..6720b73a0 100644 --- a/core/test/test_move_to.cpp +++ b/core/test/test_move_to.cpp @@ -201,7 +201,7 @@ TEST(Task, taskMoveConstructor) { t.init(); EXPECT_TRUE(t.plan(1)); } catch (const InitStageException& e) { - ADD_FAILURE() << "InitStageException:" << std::endl << e << t; + ADD_FAILURE() << "InitStageException:\n" << e << t; } } diff --git a/demo/src/alternative_path_costs.cpp b/demo/src/alternative_path_costs.cpp index 1ec77b524..d72e92bbd 100644 --- a/demo/src/alternative_path_costs.cpp +++ b/demo/src/alternative_path_costs.cpp @@ -73,7 +73,7 @@ int main(int argc, char** argv) { try { t.plan(0); } catch (const InitStageException& e) { - std::cout << e << std::endl; + std::cout << e << '\n'; } ros::spin(); diff --git a/demo/src/cartesian.cpp b/demo/src/cartesian.cpp index 5975e9689..1f7fedf60 100644 --- a/demo/src/cartesian.cpp +++ b/demo/src/cartesian.cpp @@ -142,7 +142,7 @@ int main(int argc, char** argv) { if (task.plan()) task.introspection().publishSolution(*task.solutions().front()); } catch (const InitStageException& ex) { - std::cerr << "planning failed with exception" << std::endl << ex << task; + std::cerr << "planning failed with exception\n" << ex << task; } ros::waitForShutdown(); // keep alive for interactive inspection in rviz diff --git a/demo/src/fallbacks_move_to.cpp b/demo/src/fallbacks_move_to.cpp index 05731ee19..d96c81138 100644 --- a/demo/src/fallbacks_move_to.cpp +++ b/demo/src/fallbacks_move_to.cpp @@ -123,7 +123,7 @@ int main(int argc, char** argv) { try { t.plan(); } catch (const InitStageException& e) { - std::cout << e << std::endl; + std::cout << e << '\n'; } ros::waitForShutdown(); diff --git a/demo/src/ik_clearance_cost.cpp b/demo/src/ik_clearance_cost.cpp index 37b06282d..d1b73a799 100644 --- a/demo/src/ik_clearance_cost.cpp +++ b/demo/src/ik_clearance_cost.cpp @@ -68,7 +68,7 @@ int main(int argc, char** argv) { try { t.plan(0); } catch (const InitStageException& e) { - std::cout << e << std::endl; + std::cout << e << '\n'; } ros::waitForShutdown(); diff --git a/demo/src/modular.cpp b/demo/src/modular.cpp index aa2cad750..03bc5d212 100644 --- a/demo/src/modular.cpp +++ b/demo/src/modular.cpp @@ -121,7 +121,7 @@ int main(int argc, char** argv) { if (task.plan()) task.introspection().publishSolution(*task.solutions().front()); } catch (const InitStageException& ex) { - std::cerr << "planning failed with exception" << std::endl << ex << task; + std::cerr << "planning failed with exception\n" << ex << task; } ros::waitForShutdown(); // keep alive for interactive inspection in rviz From cd0ab8838c2b9e25f86c14fa38339688125f5583 Mon Sep 17 00:00:00 2001 From: Robert Haschke Date: Sun, 22 Dec 2024 13:47:43 +0100 Subject: [PATCH 5/6] CI: Add Noble build --- .github/workflows/ci.yaml | 10 +++++----- .github/workflows/format.yaml | 8 ++++---- .pre-commit-config.yaml | 6 +++--- core/src/stages/predicate_filter.cpp | 2 -- 4 files changed, 12 insertions(+), 14 deletions(-) diff --git a/.github/workflows/ci.yaml b/.github/workflows/ci.yaml index 19d75e1d2..f907a6d6a 100644 --- a/.github/workflows/ci.yaml +++ b/.github/workflows/ci.yaml @@ -19,15 +19,15 @@ jobs: fail-fast: false matrix: env: - - IMAGE: jammy-ci - - IMAGE: noetic-source + - IMAGE: noble-ci NAME: ccov TARGET_CMAKE_ARGS: -DCMAKE_BUILD_TYPE=Debug -DCMAKE_CXX_FLAGS="--coverage" - - IMAGE: noetic-source + - IMAGE: noble-ci CLANG_TIDY: true TARGET_CMAKE_ARGS: >- -DCMAKE_BUILD_TYPE=Release -DCMAKE_CXX_FLAGS="-Werror -Wall -Wextra -Wwrite-strings -Wunreachable-code -Wpointer-arith -Wredundant-decls -Wold-style-cast" + - IMAGE: jammy-ci - IMAGE: noetic-source NAME: asan DOCKER_RUN_OPTS: >- @@ -39,7 +39,7 @@ jobs: CATKIN_LINT: true CLANG_TIDY_ARGS: -quiet -export-fixes ${{ github.workspace }}/.work/clang-tidy-fixes.yaml DOCKER_IMAGE: moveit/moveit:${{ matrix.env.IMAGE }} - UNDERLAY: ${{ matrix.env.IMAGE != 'jammy-ci' && '/root/ws_moveit/install' || '' }} + UNDERLAY: ${{ endsWith(matrix.env.IMAGE, '-source') && '/root/ws_moveit/install' || '' }} DOWNSTREAM_WORKSPACE: "github:ubi-agni/mtc_demos#master" CCACHE_DIR: ${{ github.workspace }}/.ccache BASEDIR: ${{ github.workspace }}/.work @@ -47,7 +47,7 @@ jobs: # perform full clang-tidy check only on manual trigger (workflow_dispatch), PRs do check changed files, otherwise nothing CLANG_TIDY_BASE_REF: ${{ github.event_name != 'workflow_dispatch' && (github.base_ref || github.ref) || '' }} CC: ${{ matrix.env.CLANG_TIDY && 'clang' }} - CXX: ${{ matrix.env.CLANG_TIDY && 'clang++' }} + CXX: ${{ matrix.env.CLANG_TIDY && 'clang++ -std=c++17' }} name: "${{ matrix.env.IMAGE }}${{ matrix.env.NAME && ' • ' || ''}}${{ matrix.env.NAME }}${{ matrix.env.CATKIN_LINT && ' • catkin_lint' || ''}}${{ matrix.env.CLANG_TIDY && ' • clang-tidy' || '' }}" runs-on: ubuntu-latest diff --git a/.github/workflows/format.yaml b/.github/workflows/format.yaml index a40899e8d..25af1a964 100644 --- a/.github/workflows/format.yaml +++ b/.github/workflows/format.yaml @@ -11,14 +11,14 @@ on: jobs: pre-commit: name: pre-commit - runs-on: ubuntu-20.04 + runs-on: ubuntu-latest steps: - uses: actions/checkout@v4 with: submodules: recursive - - name: Install clang-format-12 - run: sudo apt-get install clang-format-12 - - uses: rhaschke/install-catkin_lint-action@v1.0 + - name: Install clang-format-14 + run: sudo apt-get install clang-format-14 + - uses: rhaschke/install-catkin_lint-action@main with: distro: noetic - uses: pre-commit/action@v3.0.1 diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 6557cc434..51a427d3e 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -15,7 +15,7 @@ repos: # Standard hooks - repo: https://github.com/pre-commit/pre-commit-hooks - rev: v4.6.0 + rev: v5.0.0 hooks: - id: check-added-large-files - id: check-case-conflict @@ -29,7 +29,7 @@ repos: - id: trailing-whitespace - repo: https://github.com/psf/black - rev: 24.8.0 + rev: 24.10.0 hooks: - id: black args: ["--line-length", "100"] @@ -39,7 +39,7 @@ repos: - id: clang-format name: clang-format description: Format files with ClangFormat. - entry: clang-format-12 + entry: clang-format-14 language: system files: \.(c|cc|cxx|cpp|frag|glsl|h|hpp|hxx|ih|ispc|ipp|java|js|m|proto|vert)$ args: ["-fallback-style=none", "-i"] diff --git a/core/src/stages/predicate_filter.cpp b/core/src/stages/predicate_filter.cpp index d64b2cb81..869f67d01 100644 --- a/core/src/stages/predicate_filter.cpp +++ b/core/src/stages/predicate_filter.cpp @@ -80,8 +80,6 @@ void PredicateFilter::init(const moveit::core::RobotModelConstPtr& robot_model) void PredicateFilter::onNewSolution(const SolutionBase& s) { const auto& props = properties(); - // false-positive in clang-tidy 10.0.0: predicate might change comment - // NOLINTNEXTLINE(performance-unnecessary-copy-initialization) std::string comment = s.comment(); double cost = s.cost(); From 4dfcf095162e9a27c3dbaa4394e2bccfc6ea63ba Mon Sep 17 00:00:00 2001 From: Robert Haschke Date: Sun, 22 Dec 2024 13:39:20 +0100 Subject: [PATCH 6/6] clang-format-14 --- core/include/moveit/task_constructor/stage_p.h | 10 +++++++--- core/src/cost_terms.cpp | 4 ++-- core/src/stages/compute_ik.cpp | 2 +- core/src/stages/modify_planning_scene.cpp | 2 +- core/src/stages/simple_grasp.cpp | 2 +- core/test/test_stage.cpp | 2 +- .../properties/property_from_yaml.cpp | 2 +- 7 files changed, 14 insertions(+), 10 deletions(-) diff --git a/core/include/moveit/task_constructor/stage_p.h b/core/include/moveit/task_constructor/stage_p.h index b965ac198..21dcee2a0 100644 --- a/core/include/moveit/task_constructor/stage_p.h +++ b/core/include/moveit/task_constructor/stage_p.h @@ -50,9 +50,13 @@ #include // define pimpl() functions accessing correctly casted pimpl_ pointer -#define PIMPL_FUNCTIONS(Class) \ - const Class##Private* Class::pimpl() const { return static_cast(pimpl_); } \ - Class##Private* Class::pimpl() { return static_cast(pimpl_); } +#define PIMPL_FUNCTIONS(Class) \ + const Class##Private* Class::pimpl() const { \ + return static_cast(pimpl_); \ + } \ + Class##Private* Class::pimpl() { \ + return static_cast(pimpl_); \ + } namespace moveit { namespace task_constructor { diff --git a/core/src/cost_terms.cpp b/core/src/cost_terms.cpp index 4bd6ebadc..4373d7d1f 100644 --- a/core/src/cost_terms.cpp +++ b/core/src/cost_terms.cpp @@ -241,8 +241,8 @@ double Clearance::operator()(const SubTrajectory& s, std::string& comment) const auto& state_properties{ state->properties() }; auto& stage_properties{ s.creator()->properties() }; request.group_name = state_properties.hasProperty(group_property) ? - state_properties.get(group_property) : - stage_properties.get(group_property); + state_properties.get(group_property) : + stage_properties.get(group_property); // look at all forbidden collisions involving group_name request.enableGroup(state->scene()->getRobotModel()); diff --git a/core/src/stages/compute_ik.cpp b/core/src/stages/compute_ik.cpp index bf0fa4a45..9ae900043 100644 --- a/core/src/stages/compute_ik.cpp +++ b/core/src/stages/compute_ik.cpp @@ -289,7 +289,7 @@ void ComputeIK::compute() { if (value.empty()) { // property undefined // determine IK link from eef/group if (!(link = eef_jmg ? robot_model->getLinkModel(eef_jmg->getEndEffectorParentGroup().second) : - jmg->getOnlyOneEndEffectorTip())) { + jmg->getOnlyOneEndEffectorTip())) { ROS_WARN_STREAM_NAMED("ComputeIK", "Failed to derive IK target link"); return; } diff --git a/core/src/stages/modify_planning_scene.cpp b/core/src/stages/modify_planning_scene.cpp index dd24c7594..36a808d8d 100644 --- a/core/src/stages/modify_planning_scene.cpp +++ b/core/src/stages/modify_planning_scene.cpp @@ -112,7 +112,7 @@ void ModifyPlanningScene::attachObjects(planning_scene::PlanningScene& scene, if (invert) attach = !attach; obj.object.operation = attach ? static_cast(moveit_msgs::CollisionObject::ADD) : - static_cast(moveit_msgs::CollisionObject::REMOVE); + static_cast(moveit_msgs::CollisionObject::REMOVE); for (const std::string& name : pair.second.first) { obj.object.id = name; scene.processAttachedCollisionObjectMsg(obj); diff --git a/core/src/stages/simple_grasp.cpp b/core/src/stages/simple_grasp.cpp index 8268eb855..85ed2fdf8 100644 --- a/core/src/stages/simple_grasp.cpp +++ b/core/src/stages/simple_grasp.cpp @@ -129,7 +129,7 @@ void SimpleGraspBase::setup(std::unique_ptr&& generator, bool forward) { const std::string& eef = p.get("eef"); moveit_msgs::AttachedCollisionObject obj; obj.object.operation = forward ? static_cast(moveit_msgs::CollisionObject::ADD) : - static_cast(moveit_msgs::CollisionObject::REMOVE); + static_cast(moveit_msgs::CollisionObject::REMOVE); obj.link_name = scene->getRobotModel()->getEndEffector(eef)->getEndEffectorParentGroup().second; obj.object.id = p.get("object"); scene->processAttachedCollisionObjectMsg(obj); diff --git a/core/test/test_stage.cpp b/core/test/test_stage.cpp index 298d8c3fb..1a81b4387 100644 --- a/core/test/test_stage.cpp +++ b/core/test/test_stage.cpp @@ -119,7 +119,7 @@ void attachObject(PlanningScene& scene, const std::string& object, const std::st moveit_msgs::AttachedCollisionObject obj; obj.link_name = link; obj.object.operation = attach ? static_cast(moveit_msgs::CollisionObject::ADD) : - static_cast(moveit_msgs::CollisionObject::REMOVE); + static_cast(moveit_msgs::CollisionObject::REMOVE); obj.object.id = object; scene.processAttachedCollisionObjectMsg(obj); } diff --git a/visualization/motion_planning_tasks/properties/property_from_yaml.cpp b/visualization/motion_planning_tasks/properties/property_from_yaml.cpp index a46d18bff..c8763affe 100644 --- a/visualization/motion_planning_tasks/properties/property_from_yaml.cpp +++ b/visualization/motion_planning_tasks/properties/property_from_yaml.cpp @@ -53,7 +53,7 @@ class ScopedYamlEvent { public: ~ScopedYamlEvent() { yaml_event_delete(&event_); } - operator yaml_event_t const &() const { return event_; } + operator yaml_event_t const&() const { return event_; } operator yaml_event_t&() { return event_; } private: