@@ -95,6 +95,7 @@ class LambdaCostTerm : public TrajectoryCostTerm
9595 LambdaCostTerm (const SubTrajectorySignature& term);
9696 LambdaCostTerm (const SubTrajectoryShortSignature& term);
9797
98+ using TrajectoryCostTerm::operator ();
9899 double operator ()(const SubTrajectory& s, std::string& comment) const override ;
99100
100101protected:
@@ -132,6 +133,8 @@ class PathLength : public TrajectoryCostTerm
132133 PathLength (std::vector<std::string> joints);
133134 // / Limit measurements to given joints and use given weighting
134135 PathLength (std::map<std::string, double > j) : joints(std::move(j)) {}
136+
137+ using TrajectoryCostTerm::operator ();
135138 double operator ()(const SubTrajectory& s, std::string& comment) const override ;
136139
137140 std::map<std::string, double > joints; // < joint weights
@@ -145,6 +148,8 @@ class DistanceToReference : public TrajectoryCostTerm
145148 std::map<std::string, double > w = std::map<std::string, double >());
146149 DistanceToReference (const std::map<std::string, double >& ref, Mode m = Mode::AUTO,
147150 std::map<std::string, double > w = std::map<std::string, double >());
151+
152+ using TrajectoryCostTerm::operator ();
148153 double operator ()(const SubTrajectory& s, std::string& comment) const override ;
149154
150155 moveit_msgs::RobotState reference;
@@ -156,6 +161,7 @@ class DistanceToReference : public TrajectoryCostTerm
156161class TrajectoryDuration : public TrajectoryCostTerm
157162{
158163public:
164+ using TrajectoryCostTerm::operator ();
159165 double operator ()(const SubTrajectory& s, std::string& comment) const override ;
160166};
161167
@@ -167,6 +173,7 @@ class LinkMotion : public TrajectoryCostTerm
167173
168174 std::string link_name;
169175
176+ using TrajectoryCostTerm::operator ();
170177 double operator ()(const SubTrajectory& s, std::string& comment) const override ;
171178};
172179
@@ -191,6 +198,7 @@ class Clearance : public TrajectoryCostTerm
191198
192199 std::function<double (double )> distance_to_cost;
193200
201+ using TrajectoryCostTerm::operator ();
194202 double operator ()(const SubTrajectory& s, std::string& comment) const override ;
195203};
196204
0 commit comments