From 4debc3790400632bc7eaebabc1b684b322690e03 Mon Sep 17 00:00:00 2001 From: Robert Haschke Date: Thu, 11 Jul 2024 09:49:39 +0200 Subject: [PATCH] Silence gcc's overloaded-virtual warnings --- core/include/moveit/task_constructor/cost_terms.h | 8 ++++++++ core/test/test_cost_terms.cpp | 1 + 2 files changed, 9 insertions(+) diff --git a/core/include/moveit/task_constructor/cost_terms.h b/core/include/moveit/task_constructor/cost_terms.h index 9728ebaa9..353464081 100644 --- a/core/include/moveit/task_constructor/cost_terms.h +++ b/core/include/moveit/task_constructor/cost_terms.h @@ -95,6 +95,7 @@ class LambdaCostTerm : public TrajectoryCostTerm LambdaCostTerm(const SubTrajectorySignature& term); LambdaCostTerm(const SubTrajectoryShortSignature& term); + using TrajectoryCostTerm::operator(); double operator()(const SubTrajectory& s, std::string& comment) const override; protected: @@ -132,6 +133,8 @@ class PathLength : public TrajectoryCostTerm PathLength(std::vector joints); /// Limit measurements to given joints and use given weighting PathLength(std::map j) : joints(std::move(j)) {} + + using TrajectoryCostTerm::operator(); double operator()(const SubTrajectory& s, std::string& comment) const override; std::map joints; //< joint weights @@ -145,6 +148,8 @@ class DistanceToReference : public TrajectoryCostTerm std::map w = std::map()); DistanceToReference(const std::map& ref, Mode m = Mode::AUTO, std::map w = std::map()); + + using TrajectoryCostTerm::operator(); double operator()(const SubTrajectory& s, std::string& comment) const override; moveit_msgs::RobotState reference; @@ -156,6 +161,7 @@ class DistanceToReference : public TrajectoryCostTerm class TrajectoryDuration : public TrajectoryCostTerm { public: + using TrajectoryCostTerm::operator(); double operator()(const SubTrajectory& s, std::string& comment) const override; }; @@ -167,6 +173,7 @@ class LinkMotion : public TrajectoryCostTerm std::string link_name; + using TrajectoryCostTerm::operator(); double operator()(const SubTrajectory& s, std::string& comment) const override; }; @@ -191,6 +198,7 @@ class Clearance : public TrajectoryCostTerm std::function distance_to_cost; + using TrajectoryCostTerm::operator(); double operator()(const SubTrajectory& s, std::string& comment) const override; }; diff --git a/core/test/test_cost_terms.cpp b/core/test/test_cost_terms.cpp index a610ca043..4494320d1 100644 --- a/core/test/test_cost_terms.cpp +++ b/core/test/test_cost_terms.cpp @@ -157,6 +157,7 @@ TEST(CostTerm, SolutionConnected) { VerifySolutionCostTerm(Standalone& container, Stage* creator) : container_{ container }, creator_{ creator } {} + using TrajectoryCostTerm::operator(); double operator()(const SubTrajectory& s, std::string& /*comment*/) const override { EXPECT_EQ(&*container_.state_start, const_cast(container_.pimpl())->internalToExternalMap().at(s.start()))