Fix names of trampoline classes

Using template names T is not a good idea, because this name is used
verbatim for some error reporting, resulting e.g. in:
Tried to call pure virtual function "T::canCompute"
This commit is contained in:
Robert Haschke 2021-05-21 11:40:12 +02:00
parent 0967aa808b
commit 9f7139f376

View File

@ -49,35 +49,35 @@ namespace solvers {
class PlannerInterface; class PlannerInterface;
} }
template <class T = Stage> template <class Stage = moveit::task_constructor::Stage>
class PyStage : public T, public pybind11::trampoline_self_life_support class PyStage : public Stage, public pybind11::trampoline_self_life_support
{ {
public: public:
using T::T; using Stage::Stage;
void init(const moveit::core::RobotModelConstPtr& robot_model) override { void init(const moveit::core::RobotModelConstPtr& robot_model) override {
PYBIND11_OVERRIDE(void, T, init, robot_model); PYBIND11_OVERRIDE(void, Stage, init, robot_model);
} }
void reset() override { PYBIND11_OVERRIDE(void, T, reset, ); } void reset() override { PYBIND11_OVERRIDE(void, Stage, reset, ); }
}; };
template <class T = Generator> template <class Generator = moveit::task_constructor::Generator>
class PyGenerator : public PyStage<T> class PyGenerator : public PyStage<Generator>
{ {
public: public:
using PyStage<T>::PyStage; using PyStage<Generator>::PyStage;
bool canCompute() const override { PYBIND11_OVERRIDE_PURE(bool, T, canCompute, ); } bool canCompute() const override { PYBIND11_OVERRIDE_PURE(bool, Generator, canCompute, ); }
void compute() override { PYBIND11_OVERRIDE_PURE(void, T, compute, ); } void compute() override { PYBIND11_OVERRIDE_PURE(void, Generator, compute, ); }
}; };
template <class T = MonitoringGenerator> template <class MonitoringGenerator = moveit::task_constructor::MonitoringGenerator>
class PyMonitoringGenerator : public PyGenerator<T> class PyMonitoringGenerator : public PyGenerator<MonitoringGenerator>
{ {
public: public:
using PyGenerator<T>::PyGenerator; using PyGenerator<MonitoringGenerator>::PyGenerator;
void onNewSolution(const SolutionBase& s) override { void onNewSolution(const SolutionBase& s) override {
// pass solution as pointer to trigger passing by reference // pass solution as pointer to trigger passing by reference
PYBIND11_OVERRIDE_PURE(void, T, onNewSolution, &s); PYBIND11_OVERRIDE_PURE(void, MonitoringGenerator, onNewSolution, &s);
} }
}; };
@ -87,18 +87,18 @@ public:
using MonitoringGenerator::onNewSolution; using MonitoringGenerator::onNewSolution;
}; };
template <class T = PropagatingEitherWay> template <class PropagatingEitherWay = moveit::task_constructor::PropagatingEitherWay>
class PyPropagatingEitherWay : public PyStage<T> class PyPropagatingEitherWay : public PyStage<PropagatingEitherWay>
{ {
public: public:
using PyStage<T>::PyStage; using PyStage<PropagatingEitherWay>::PyStage;
void computeForward(const InterfaceState& from_state) override { void computeForward(const InterfaceState& from_state) override {
// pass InterfaceState as pointer to trigger passing by reference // pass InterfaceState as pointer to trigger passing by reference
PYBIND11_OVERRIDE_PURE(void, T, computeForward, &from_state); PYBIND11_OVERRIDE_PURE(void, PropagatingEitherWay, computeForward, &from_state);
} }
void computeBackward(const InterfaceState& to_state) override { void computeBackward(const InterfaceState& to_state) override {
// pass InterfaceState as pointer to trigger passing by reference // pass InterfaceState as pointer to trigger passing by reference
PYBIND11_OVERRIDE_PURE(void, T, computeBackward, &to_state); PYBIND11_OVERRIDE_PURE(void, PropagatingEitherWay, computeBackward, &to_state);
} }
}; };