From 4202550eaf89b0f3a0790bfa4e58a33db5d1051a Mon Sep 17 00:00:00 2001 From: Robert Haschke Date: Thu, 26 Oct 2023 16:32:08 +0200 Subject: [PATCH] Update to clang-format-12 --- .github/workflows/format.yaml | 4 +- .pre-commit-config.yaml | 2 +- .../include/moveit/task_constructor/stage_p.h | 10 +- core/src/container.cpp | 103 +++++++++--------- 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 +- 9 files changed, 63 insertions(+), 68 deletions(-) diff --git a/.github/workflows/format.yaml b/.github/workflows/format.yaml index 3a61c608d..66f60b910 100644 --- a/.github/workflows/format.yaml +++ b/.github/workflows/format.yaml @@ -16,8 +16,8 @@ jobs: - uses: actions/checkout@v3 with: submodules: recursive - - name: Install clang-format-10 - run: sudo apt-get install clang-format-10 + - name: Install clang-format-12 + run: sudo apt-get install clang-format-12 - uses: rhaschke/install-catkin_lint-action@v1.0 with: distro: noetic diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 961699b0e..f99a91c48 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -39,7 +39,7 @@ repos: - id: clang-format name: clang-format description: Format files with ClangFormat. - entry: clang-format-10 + entry: clang-format-12 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/include/moveit/task_constructor/stage_p.h b/core/include/moveit/task_constructor/stage_p.h index c22da5616..5683ae327 100644 --- a/core/include/moveit/task_constructor/stage_p.h +++ b/core/include/moveit/task_constructor/stage_p.h @@ -50,13 +50,9 @@ #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/container.cpp b/core/src/container.cpp index 53cd40127..79cbeef22 100644 --- a/core/src/container.cpp +++ b/core/src/container.cpp @@ -646,8 +646,8 @@ void SerialContainerPrivate::resolveInterface(InterfaceFlags expected) { exceptions.append(e); } - required_interface_ = (first.pimpl()->interfaceFlags() & START_IF_MASK) | // clang-format off - (last.pimpl()->interfaceFlags() & END_IF_MASK); // clang-format off + required_interface_ = (first.pimpl()->interfaceFlags() & START_IF_MASK) | // + (last.pimpl()->interfaceFlags() & END_IF_MASK); if (exceptions) throw exceptions; @@ -702,7 +702,6 @@ void SerialContainer::compute() { } } - ParallelContainerBasePrivate::ParallelContainerBasePrivate(ParallelContainerBase* me, const std::string& name) : ContainerBasePrivate(me, name) {} @@ -741,11 +740,11 @@ void ParallelContainerBasePrivate::initializeExternalInterfaces() { // States received by the container need to be copied to all children's pull interfaces. if (requiredInterface() & READS_START) starts() = std::make_shared([this](Interface::iterator external, Interface::UpdateFlags updated) { - this->propagateStateToAllChildren(external, updated); + this->propagateStateToAllChildren(external, updated); }); if (requiredInterface() & READS_END) ends() = std::make_shared([this](Interface::iterator external, Interface::UpdateFlags updated) { - this->propagateStateToAllChildren(external, updated); + this->propagateStateToAllChildren(external, updated); }); } @@ -761,11 +760,11 @@ void ParallelContainerBasePrivate::validateInterfaces(const StagePrivate& child, } if (!valid) - throw InitStageException(*me_, fmt::format("interface of '{0}' ({2} {3}) does not match {1} ({4} {5}).", - child.name(), - (first ? "external one" : "other children's"), - flowSymbol(child_interface), flowSymbol(child_interface), - flowSymbol(external), flowSymbol(external))); + throw InitStageException( + *me_, fmt::format("interface of '{0}' ({2} {3}) does not match {1} ({4} {5}).", child.name(), + (first ? "external one" : "other children's"), // + flowSymbol(child_interface), flowSymbol(child_interface), + flowSymbol(external), flowSymbol(external))); } void ParallelContainerBasePrivate::validateConnectivity() const { @@ -779,7 +778,8 @@ void ParallelContainerBasePrivate::validateConnectivity() const { } template -void ParallelContainerBasePrivate::propagateStateToAllChildren(Interface::iterator external, Interface::UpdateFlags updated) { +void ParallelContainerBasePrivate::propagateStateToAllChildren(Interface::iterator external, + Interface::UpdateFlags updated) { for (const Stage::pointer& stage : children()) copyState(external, stage->pimpl()->pullInterface(), updated); } @@ -789,8 +789,8 @@ ParallelContainerBase::ParallelContainerBase(const std::string& name) : ParallelContainerBase(new ParallelContainerBasePrivate(this, name)) {} void ParallelContainerBase::liftSolution(const SolutionBase& solution, double cost, std::string comment) { - pimpl()->liftSolution(std::make_shared(this, &solution, cost, std::move(comment)), - solution.start(), solution.end()); + pimpl()->liftSolution(std::make_shared(this, &solution, cost, std::move(comment)), solution.start(), + solution.end()); } void ParallelContainerBase::spawn(InterfaceState&& state, SubTrajectory&& t) { @@ -871,7 +871,7 @@ void Fallbacks::onNewSolution(const SolutionBase& s) { } inline void Fallbacks::replaceImpl() { - FallbacksPrivate *impl = pimpl(); + FallbacksPrivate* impl = pimpl(); if (pimpl()->interfaceFlags() == pimpl()->requiredInterface()) return; switch (pimpl()->requiredInterface()) { @@ -894,11 +894,10 @@ inline void Fallbacks::replaceImpl() { pimpl_ = impl; } -FallbacksPrivate::FallbacksPrivate(Fallbacks* me, const std::string& name) - : ParallelContainerBasePrivate(me, name) {} +FallbacksPrivate::FallbacksPrivate(Fallbacks* me, const std::string& name) : ParallelContainerBasePrivate(me, name) {} FallbacksPrivate::FallbacksPrivate(FallbacksPrivate&& other) -: ParallelContainerBasePrivate(static_cast(other.me()), "") { + : ParallelContainerBasePrivate(static_cast(other.me()), "") { // move contents of other this->ParallelContainerBasePrivate::operator=(std::move(other)); } @@ -928,8 +927,8 @@ void FallbacksPrivateCommon::reset() { } bool FallbacksPrivateCommon::canCompute() const { - while(current_ != children().end() && // not completely exhausted - !(*current_)->pimpl()->canCompute()) // but current child cannot compute + while (current_ != children().end() && // not completely exhausted + !(*current_)->pimpl()->canCompute()) // but current child cannot compute return const_cast(this)->nextJob(); // advance to next job // return value: current child is well defined and thus can compute? @@ -946,8 +945,9 @@ inline void FallbacksPrivateCommon::nextChild() { ++current_; // advance to next child } -FallbacksPrivateGenerator::FallbacksPrivateGenerator(FallbacksPrivate&& old) - : FallbacksPrivateCommon(std::move(old)) { FallbacksPrivateCommon::reset(); } +FallbacksPrivateGenerator::FallbacksPrivateGenerator(FallbacksPrivate&& old) : FallbacksPrivateCommon(std::move(old)) { + FallbacksPrivateCommon::reset(); +} bool FallbacksPrivateGenerator::nextJob() { assert(current_ != children().end() && !(*current_)->pimpl()->canCompute()); @@ -958,27 +958,27 @@ bool FallbacksPrivateGenerator::nextJob() { return false; } - do { nextChild(); } - while (current_ != children().end() && !(*current_)->pimpl()->canCompute()); + do { + nextChild(); + } while (current_ != children().end() && !(*current_)->pimpl()->canCompute()); // return value shall indicate current_->canCompute() return current_ != children().end(); } - FallbacksPrivatePropagator::FallbacksPrivatePropagator(FallbacksPrivate&& old) - : FallbacksPrivateCommon(std::move(old)) { + : FallbacksPrivateCommon(std::move(old)) { switch (requiredInterface()) { - case PROPAGATE_FORWARDS: - dir_ = Interface::FORWARD; - starts() = std::make_shared(); - break; - case PROPAGATE_BACKWARDS: - dir_ = Interface::BACKWARD; - ends() = std::make_shared(); - break; - default: - assert(false); + case PROPAGATE_FORWARDS: + dir_ = Interface::FORWARD; + starts() = std::make_shared(); + break; + case PROPAGATE_BACKWARDS: + dir_ = Interface::BACKWARD; + ends() = std::make_shared(); + break; + default: + assert(false); } FallbacksPrivatePropagator::reset(); } @@ -998,8 +998,8 @@ bool FallbacksPrivatePropagator::nextJob() { assert(current_ != children().end() && !(*current_)->pimpl()->canCompute()); const auto jobs = pullInterface(dir_); - if (job_ != jobs->end()) { // current job exists, but is exhausted on current child - if (!job_has_solutions_) // job didn't produce solutions -> feed to next child + if (job_ != jobs->end()) { // current job exists, but is exhausted on current child + if (!job_has_solutions_) // job didn't produce solutions -> feed to next child nextChild(); else current_ = children().end(); // indicate that this job is exhausted on all children @@ -1017,9 +1017,9 @@ bool FallbacksPrivatePropagator::nextJob() { // pick next job if needed and possible if (job_ == jobs->end()) { // need to pick next job if (!jobs->empty() && jobs->front()->priority().enabled()) - job_ = jobs->begin(); + job_ = jobs->begin(); else - return false; // no more jobs available + return false; // no more jobs available } // When arriving here, we have a valid job_ and a current_ child to feed it. Let's do that. @@ -1027,13 +1027,11 @@ bool FallbacksPrivatePropagator::nextJob() { return true; } - -FallbacksPrivateConnect::FallbacksPrivateConnect(FallbacksPrivate&& old) - : FallbacksPrivate(std::move(old)) { - starts_ = std::make_shared( - std::bind(&FallbacksPrivateConnect::propagateStateUpdate, this, std::placeholders::_1, std::placeholders::_2)); - ends_ = std::make_shared( - std::bind(&FallbacksPrivateConnect::propagateStateUpdate, this, std::placeholders::_1, std::placeholders::_2)); +FallbacksPrivateConnect::FallbacksPrivateConnect(FallbacksPrivate&& old) : FallbacksPrivate(std::move(old)) { + starts_ = std::make_shared(std::bind(&FallbacksPrivateConnect::propagateStateUpdate, + this, std::placeholders::_1, std::placeholders::_2)); + ends_ = std::make_shared(std::bind(&FallbacksPrivateConnect::propagateStateUpdate, + this, std::placeholders::_1, std::placeholders::_2)); FallbacksPrivateConnect::reset(); } @@ -1050,7 +1048,7 @@ void FallbacksPrivateConnect::propagateStateUpdate(Interface::iterator external, } bool FallbacksPrivateConnect::canCompute() const { - for (auto it=children().begin(), end=children().end(); it!=end; ++it) + for (auto it = children().begin(), end = children().end(); it != end; ++it) if ((*it)->pimpl()->canCompute()) { active_ = it; return true; @@ -1067,7 +1065,8 @@ void FallbacksPrivateConnect::compute() { void FallbacksPrivateConnect::onNewFailure(const Stage& child, const InterfaceState* from, const InterfaceState* to) { // expect failure to be reported from active child - assert(active_ != children().end() && active_->get() == &child); (void)child; + assert(active_ != children().end() && active_->get() == &child); + (void)child; // ... thus we can use std::next(active_) to find the next child auto next = std::next(active_); @@ -1088,7 +1087,6 @@ void FallbacksPrivateConnect::onNewFailure(const Stage& child, const InterfaceSt parent()->pimpl()->onNewFailure(*me(), from, to); } - MergerPrivate::MergerPrivate(Merger* me, const std::string& name) : ParallelContainerBasePrivate(me, name) {} void MergerPrivate::resolveInterface(InterfaceFlags expected) { @@ -1110,7 +1108,7 @@ void MergerPrivate::resolveInterface(InterfaceFlags expected) { Merger::Merger(const std::string& name) : Merger(new MergerPrivate(this, name)) { properties().declare("time_parameterization", - std::make_shared()); + std::make_shared()); } void Merger::reset() { @@ -1287,8 +1285,9 @@ void MergerPrivate::merge(const ChildSolutionList& sub_solutions, oss << "Invalid waypoint(s): "; if (invalid_index.size() == merged->getWayPointCount()) oss << "all"; - else for (size_t i : invalid_index) - oss << i << ", "; + else + for (size_t i : invalid_index) + oss << i << ", "; t.setComment(oss.str()); } else { // accumulate costs and markers diff --git a/core/src/cost_terms.cpp b/core/src/cost_terms.cpp index d9996d2c8..8ba3aac91 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 aeae71ccd..4822998ad 100644 --- a/core/src/stages/compute_ik.cpp +++ b/core/src/stages/compute_ik.cpp @@ -287,7 +287,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 43cf19287..63a5acdc6 100644 --- a/core/src/stages/modify_planning_scene.cpp +++ b/core/src/stages/modify_planning_scene.cpp @@ -103,7 +103,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 85ed2fdf8..8268eb855 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 1a81b4387..298d8c3fb 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); }