Skip to content

Commit

Permalink
Silence gcc's overloaded-virtual warnings
Browse files Browse the repository at this point in the history
  • Loading branch information
rhaschke committed Jul 11, 2024
1 parent 702710d commit 4debc37
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 0 deletions.
8 changes: 8 additions & 0 deletions core/include/moveit/task_constructor/cost_terms.h
Original file line number Diff line number Diff line change
Expand Up @@ -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:
Expand Down Expand Up @@ -132,6 +133,8 @@ class PathLength : public TrajectoryCostTerm
PathLength(std::vector<std::string> joints);
/// Limit measurements to given joints and use given weighting
PathLength(std::map<std::string, double> j) : joints(std::move(j)) {}

using TrajectoryCostTerm::operator();
double operator()(const SubTrajectory& s, std::string& comment) const override;

std::map<std::string, double> joints; //< joint weights
Expand All @@ -145,6 +148,8 @@ class DistanceToReference : public TrajectoryCostTerm
std::map<std::string, double> w = std::map<std::string, double>());
DistanceToReference(const std::map<std::string, double>& ref, Mode m = Mode::AUTO,
std::map<std::string, double> w = std::map<std::string, double>());

using TrajectoryCostTerm::operator();
double operator()(const SubTrajectory& s, std::string& comment) const override;

moveit_msgs::RobotState reference;
Expand All @@ -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;
};

Expand All @@ -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;
};

Expand All @@ -191,6 +198,7 @@ class Clearance : public TrajectoryCostTerm

std::function<double(double)> distance_to_cost;

using TrajectoryCostTerm::operator();
double operator()(const SubTrajectory& s, std::string& comment) const override;
};

Expand Down
1 change: 1 addition & 0 deletions core/test/test_cost_terms.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -157,6 +157,7 @@ TEST(CostTerm, SolutionConnected) {
VerifySolutionCostTerm(Standalone<SerialContainer>& 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<const SerialContainerPrivate*>(container_.pimpl())->internalToExternalMap().at(s.start()))
Expand Down

0 comments on commit 4debc37

Please sign in to comment.