diff --git a/.github/workflows/ci.yaml b/.github/workflows/ci.yaml index 702e716ce..faa6816c0 100644 --- a/.github/workflows/ci.yaml +++ b/.github/workflows/ci.yaml @@ -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.CLANG_TIDY && ' • clang-tidy' || '' }}" runs-on: ubuntu-latest diff --git a/.github/workflows/format.yaml b/.github/workflows/format.yaml index b9e129e32..7d1e396cb 100644 --- a/.github/workflows/format.yaml +++ b/.github/workflows/format.yaml @@ -18,7 +18,7 @@ jobs: submodules: recursive - name: Install clang-format-14 run: sudo apt-get install clang-format-14 - - uses: rhaschke/pre-commit-action@main + - uses: pre-commit/action@v3.0.1 id: precommit - name: Upload pre-commit changes if: failure() && steps.precommit.outcome == 'failure' diff --git a/core/include/moveit/task_constructor/cost_terms.h b/core/include/moveit/task_constructor/cost_terms.h index e52864dc2..68b84e2b5 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/solvers/cartesian_path.h b/core/include/moveit/task_constructor/solvers/cartesian_path.h index c84b6a270..db564ff5d 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/stage.h b/core/include/moveit/task_constructor/stage.h index c7573c13c..dfeb4c1df 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 23098ae48..b413da151 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 86eb0bbf9..c6643daff 100644 --- a/core/include/moveit/task_constructor/stages/generate_random_pose.h +++ b/core/include/moveit/task_constructor/stages/generate_random_pose.h @@ -56,8 +56,8 @@ 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; - enum PoseDimension + using PoseDimensionSampler = std::function; + 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 0dac14662..ff87e355d 100644 --- a/core/include/moveit/task_constructor/storage.h +++ b/core/include/moveit/task_constructor/storage.h @@ -81,7 +81,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 @@ -198,12 +198,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/python/bindings/src/properties.cpp b/core/python/bindings/src/properties.cpp index 4330d0f80..b6553f608 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/src/container.cpp b/core/src/container.cpp index 7269a8236..e5c255820 100644 --- a/core/src/container.cpp +++ b/core/src/container.cpp @@ -63,24 +63,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'; } } @@ -460,7 +460,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 @@ -469,7 +469,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 ebd3bfee7..d938f95ee 100644 --- a/core/src/introspection.cpp +++ b/core/src/introspection.cpp @@ -206,7 +206,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 9dba29cd2..085a9d75c 100644 --- a/core/src/stage.cpp +++ b/core/src/stage.cpp @@ -91,9 +91,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; } @@ -841,10 +841,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/src/stages/predicate_filter.cpp b/core/src/stages/predicate_filter.cpp index 1f8a9fc00..39c7a5111 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(); diff --git a/core/test/pick_pa10.cpp b/core/test/pick_pa10.cpp index 937034d22..5ec18b8fc 100644 --- a/core/test/pick_pa10.cpp +++ b/core/test/pick_pa10.cpp @@ -180,7 +180,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 0b15fc7e4..95e77343c 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 377f63b59..fcbf0c53f 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/stage_mockups.h b/core/test/stage_mockups.h index d17505d29..f36cb08e3 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 diff --git a/core/test/test_container.cpp b/core/test/test_container.cpp index aecd598f3..ddd0dc4e2 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, @@ -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 68ebacc86..e38a8178d 100644 --- a/core/test/test_move_to.cpp +++ b/core/test/test_move_to.cpp @@ -207,7 +207,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 dfab41041..ae380aa7d 100644 --- a/demo/src/alternative_path_costs.cpp +++ b/demo/src/alternative_path_costs.cpp @@ -77,7 +77,7 @@ int main(int argc, char** argv) { try { t.plan(0); } catch (const InitStageException& e) { - std::cout << e << std::endl; + std::cout << e << '\n'; } // keep alive for interactive inspection in rviz diff --git a/demo/src/cartesian.cpp b/demo/src/cartesian.cpp index 42524e67d..02733067c 100644 --- a/demo/src/cartesian.cpp +++ b/demo/src/cartesian.cpp @@ -133,7 +133,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; } // keep alive for interactive inspection in rviz diff --git a/demo/src/fallbacks_move_to.cpp b/demo/src/fallbacks_move_to.cpp index 212f19c16..ab093a902 100644 --- a/demo/src/fallbacks_move_to.cpp +++ b/demo/src/fallbacks_move_to.cpp @@ -125,7 +125,7 @@ int main(int argc, char** argv) { try { t.plan(); } catch (const InitStageException& e) { - std::cout << e << std::endl; + std::cout << e << '\n'; } // keep alive for interactive inspection in rviz diff --git a/demo/src/ik_clearance_cost.cpp b/demo/src/ik_clearance_cost.cpp index abc4c8fdd..4691d224c 100644 --- a/demo/src/ik_clearance_cost.cpp +++ b/demo/src/ik_clearance_cost.cpp @@ -70,7 +70,7 @@ int main(int argc, char** argv) { try { t.plan(0); } catch (const InitStageException& e) { - std::cout << e << std::endl; + std::cout << e << '\n'; } // Keep introspection alive diff --git a/demo/src/modular.cpp b/demo/src/modular.cpp index 2eb016f96..4807c19d4 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; } // keep alive for interactive inspection in rviz 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 31130e50e..47da29b7d 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 03f3cfac6..d28cfd60e 100644 --- a/visualization/motion_planning_tasks/src/remote_task_model.cpp +++ b/visualization/motion_planning_tasks/src/remote_task_model.cpp @@ -55,7 +55,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 c53de7dbf..7145e48b4 100644 --- a/visualization/motion_planning_tasks/src/task_list_model.h +++ b/visualization/motion_planning_tasks/src/task_list_model.h @@ -79,7 +79,7 @@ class BaseTaskModel : public QAbstractItemModel rviz_common::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 59c0eed8c..b1deca973 100644 --- a/visualization/motion_planning_tasks/src/task_panel.h +++ b/visualization/motion_planning_tasks/src/task_panel.h @@ -120,7 +120,7 @@ class TaskView : public SubPanel protected: // configuration settings - enum TaskExpand + enum TaskExpand : uint8_t { EXPAND_TOP = 1, EXPAND_ALL, @@ -132,7 +132,7 @@ class TaskView : public SubPanel rviz_common::properties::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,