Skip to content

Commit

Permalink
(PyKDL) fix return type and bound name (#465)
Browse files Browse the repository at this point in the history
  • Loading branch information
MatthijsBurgh authored Oct 18, 2024
1 parent d2c989d commit b8c7473
Showing 1 changed file with 3 additions and 3 deletions.
6 changes: 3 additions & 3 deletions python_orocos_kdl/PyKDL/kinfam.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -247,9 +247,9 @@ void init_kinfam(pybind11::module &m)
});

m.def("SetToZero", (void (*)(Jacobian&)) &KDL::SetToZero, py::arg("jac"));
m.def("changeRefPoint", (void (*)(const Jacobian&, const Vector&, Jacobian&)) &KDL::changeRefPoint, py::arg("src"), py::arg("base"), py::arg("dest"));
m.def("changeBase", (void (*)(const Jacobian&, const Rotation&, Jacobian&)) &KDL::changeBase, py::arg("src"), py::arg("rot"), py::arg("dest"));
m.def("SetToZero", (void (*)(const Jacobian&, const Frame&, Jacobian&)) &KDL::changeRefFrame, py::arg("src"), py::arg("frame"), py::arg("dest"));
m.def("changeRefPoint", (bool (*)(const Jacobian&, const Vector&, Jacobian&)) &KDL::changeRefPoint, py::arg("src"), py::arg("base"), py::arg("dest"));
m.def("changeBase", (bool (*)(const Jacobian&, const Rotation&, Jacobian&)) &KDL::changeBase, py::arg("src"), py::arg("rot"), py::arg("dest"));
m.def("changeRefFrame", (bool (*)(const Jacobian&, const Frame&, Jacobian&)) &KDL::changeRefFrame, py::arg("src"), py::arg("frame"), py::arg("dest"));


// --------------------
Expand Down

0 comments on commit b8c7473

Please sign in to comment.