Skip to content

Commit 6406459

Browse files
committed
feat: pybind trampoline and constructor for kinematics
1 parent d79efec commit 6406459

File tree

1 file changed

+28
-1
lines changed

1 file changed

+28
-1
lines changed

src/pybind/rcs.cpp

Lines changed: 28 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -183,6 +183,29 @@ class PyHand : public rcs::common::Hand {
183183
}
184184
};
185185

186+
// trampoline kinematics
187+
class PyKinematics : public rcs::common::Kinematics {
188+
// TODO: use line below when upgraded to pybind11 3.x
189+
// public py::trampoline_self_life_support {
190+
public:
191+
using rcs::common::Kinematics::Kinematics; // Inherit constructors
192+
193+
std::optional<rcs::common::VectorXd> inverse(
194+
const rcs::common::Pose& pose, const rcs::common::VectorXd& q0,
195+
const rcs::common::Pose& tcp_offset =
196+
rcs::common::Pose::Identity()) override {
197+
PYBIND11_OVERRIDE_PURE(std::optional<rcs::common::VectorXd>,
198+
rcs::common::Kinematics, inverse, pose, q0,
199+
tcp_offset);
200+
}
201+
202+
rcs::common::Pose forward(const rcs::common::VectorXd& q0,
203+
const rcs::common::Pose& tcp_offset) override {
204+
PYBIND11_OVERRIDE_PURE(rcs::common::Pose, rcs::common::Kinematics, forward,
205+
q0, tcp_offset);
206+
}
207+
};
208+
186209
PYBIND11_MODULE(_core, m) {
187210
m.doc() = R"pbdoc(
188211
Robot Control Stack Python Bindings
@@ -296,8 +319,12 @@ PYBIND11_MODULE(_core, m) {
296319
return rcs::common::Pose(t);
297320
}));
298321

299-
py::class_<rcs::common::Kinematics, std::shared_ptr<rcs::common::Kinematics>>(
322+
py::class_<rcs::common::Kinematics, PyKinematics,
323+
std::shared_ptr<rcs::common::Kinematics>>(
324+
// TODO: use line below when upgraded to pybind11 3.x
325+
// py::class_<rcs::common::Kinematics, PyKinematics, py::smart_holder>(
300326
common, "Kinematics")
327+
.def(py::init<>())
301328
.def("inverse", &rcs::common::Kinematics::inverse, py::arg("pose"),
302329
py::arg("q0"), py::arg("tcp_offset") = rcs::common::Pose::Identity())
303330
.def("forward", &rcs::common::Kinematics::forward, py::arg("q0"),

0 commit comments

Comments
 (0)