diff --git a/core/include/moveit/task_constructor/cost_queue.h b/core/include/moveit/task_constructor/cost_queue.h index a8f9d78a..78091aa7 100644 --- a/core/include/moveit/task_constructor/cost_queue.h +++ b/core/include/moveit/task_constructor/cost_queue.h @@ -7,12 +7,12 @@ #include /// ValueOrPointeeLess provides correct comparison for plain and pointer-like types -template +template struct ValueOrPointeeLess : public std::less {}; /// The following template-specialization is for pointer-like types template -struct ValueOrPointeeLess(), std::declval())> { +struct ValueOrPointeeLess() < *std::declval())> { bool operator()(const T& x, const T& y) const { return *x < *y; } diff --git a/core/include/moveit/task_constructor/storage.h b/core/include/moveit/task_constructor/storage.h index 27da8fdc..33d10635 100644 --- a/core/include/moveit/task_constructor/storage.h +++ b/core/include/moveit/task_constructor/storage.h @@ -192,6 +192,8 @@ class StagePrivate; /// abstract base class for solutions (primitive and sequences) class SolutionBase { public: + virtual ~SolutionBase() = default; + inline const InterfaceState* start() const { return start_; } inline const InterfaceState* end() const { return end_; } diff --git a/core/include/moveit/task_constructor/task.h b/core/include/moveit/task_constructor/task.h index b71098d5..6356ebcc 100644 --- a/core/include/moveit/task_constructor/task.h +++ b/core/include/moveit/task_constructor/task.h @@ -89,7 +89,7 @@ public: // TODO: use Stage::insert as well? void add(Stage::pointer &&stage); - void clear() override; + void clear() final; /// enable introspection publishing for use with rviz void enableIntrospection(bool enable = true); @@ -103,7 +103,7 @@ public: void erase(TaskCallbackList::const_iterator which); /// reset all stages - void reset() override; + void reset() final; /// initialize all stages with given scene void init(); diff --git a/core/src/container.cpp b/core/src/container.cpp index a8efbe12..e12a5475 100644 --- a/core/src/container.cpp +++ b/core/src/container.cpp @@ -836,7 +836,7 @@ WrapperBase::WrapperBase(const std::string &name, Stage::pointer &&child) WrapperBase::WrapperBase(WrapperBasePrivate *impl, Stage::pointer &&child) : ParallelContainerBase(impl) { - if (child) insert(std::move(child)); + if (child) WrapperBase::insert(std::move(child)); } bool WrapperBase::insert(Stage::pointer &&stage, int before) diff --git a/core/src/stages/compute_ik.cpp b/core/src/stages/compute_ik.cpp index 318d5b73..56fd6c69 100644 --- a/core/src/stages/compute_ik.cpp +++ b/core/src/stages/compute_ik.cpp @@ -379,7 +379,7 @@ void ComputeIK::compute() tried_current_state_as_seed= true; size_t previous = ik_solutions.size(); - bool succeeded = sandbox_state.setFromIK(jmg, target_pose, link->getName(), 1, remaining_time, isValid); + bool succeeded = sandbox_state.setFromIK(jmg, target_pose, link->getName(), remaining_time, isValid); auto now = std::chrono::steady_clock::now(); remaining_time -= std::chrono::duration(now - start_time).count(); diff --git a/core/src/stages/generate_place_pose.cpp b/core/src/stages/generate_place_pose.cpp index 39683eb0..7e18247d 100644 --- a/core/src/stages/generate_place_pose.cpp +++ b/core/src/stages/generate_place_pose.cpp @@ -153,6 +153,8 @@ void GeneratePlacePose::compute() { target_pose.linear() = orig_object_pose.linear(); spawner(target_pose, 1); return; + default: + break; } } diff --git a/core/src/stages/simple_grasp.cpp b/core/src/stages/simple_grasp.cpp index 2e96a3af..d4cb4224 100644 --- a/core/src/stages/simple_grasp.cpp +++ b/core/src/stages/simple_grasp.cpp @@ -91,7 +91,7 @@ void SimpleGraspBase::setup(std::unique_ptr&& generator, bool forward) p.declare("object"); p.configureInitFrom(Stage::PARENT | Stage::INTERFACE, { "eef", "object" }); - allow_touch->setCallback([this, forward](const planning_scene::PlanningScenePtr& scene, const PropertyMap& p){ + allow_touch->setCallback([forward](const planning_scene::PlanningScenePtr& scene, const PropertyMap& p){ collision_detection::AllowedCollisionMatrix& acm = scene->getAllowedCollisionMatrixNonConst(); const std::string& eef = p.get("eef"); const std::string& object = p.get("object"); @@ -125,7 +125,7 @@ void SimpleGraspBase::setup(std::unique_ptr&& generator, bool forward) p.declare("object"); p.configureInitFrom(Stage::PARENT | Stage::INTERFACE, { "eef", "object" }); - attach->setCallback([this, forward](const planning_scene::PlanningScenePtr& scene, const PropertyMap& p){ + attach->setCallback([forward](const planning_scene::PlanningScenePtr& scene, const PropertyMap& p){ const std::string& eef = p.get("eef"); moveit_msgs::AttachedCollisionObject obj; obj.object.operation = forward ? (int8_t) moveit_msgs::CollisionObject::ADD diff --git a/core/src/task.cpp b/core/src/task.cpp index b4e517b9..8060cc04 100644 --- a/core/src/task.cpp +++ b/core/src/task.cpp @@ -187,7 +187,7 @@ void Task::enableIntrospection(bool enable) else if (!enable && introspection_) { // reset introspection instance of all stages pimpl()->setIntrospection(nullptr); - pimpl()->traverseStages([this](Stage& stage, int) { + pimpl()->traverseStages([](Stage& stage, int) { stage.pimpl()->setIntrospection(nullptr); return true; }, 1, UINT_MAX); diff --git a/core/test/test_stage.cpp b/core/test/test_stage.cpp index 7a5a8073..b4dda805 100644 --- a/core/test/test_stage.cpp +++ b/core/test/test_stage.cpp @@ -25,7 +25,7 @@ public: pimpl()->setNextStarts(next); } - void init(const moveit::core::RobotModelConstPtr &robot_model) { + void init(const moveit::core::RobotModelConstPtr &robot_model) override { ps.reset((new PlanningScene(robot_model))); } diff --git a/visualization/motion_planning_tasks/properties/property_from_yaml.cpp b/visualization/motion_planning_tasks/properties/property_from_yaml.cpp index a64b7741..1536732e 100644 --- a/visualization/motion_planning_tasks/properties/property_from_yaml.cpp +++ b/visualization/motion_planning_tasks/properties/property_from_yaml.cpp @@ -133,6 +133,7 @@ rviz::Property* Parser::process(const yaml_event_t& event, case YAML_SEQUENCE_START_EVENT: return processSequence(name, description, old); case YAML_MAPPING_START_EVENT: return processMapping(name, description, old); case YAML_SCALAR_EVENT: return createScalar(name, description, byteArray(event), old); + default: break; } assert(false); // should not be reached }