diff --git a/subprojects/robotpy-wpimath/gen/geometry/Ellipse2d.yml b/subprojects/robotpy-wpimath/gen/geometry/Ellipse2d.yml index c417c1bc..1951eebb 100644 --- a/subprojects/robotpy-wpimath/gen/geometry/Ellipse2d.yml +++ b/subprojects/robotpy-wpimath/gen/geometry/Ellipse2d.yml @@ -42,7 +42,23 @@ inline_code: | .def_property_readonly("ysemiaxis_feet", [](Ellipse2d &self) -> units::foot_t { return self.YSemiAxis(); }) - .def("__repr__", py::overload_cast(&rpy::toString)); + .def("__repr__", py::overload_cast(&rpy::toString)) + .def(py::pickle( + [](const Ellipse2d &self) { // __getstate__ + return py::make_tuple(self.Center(), self.XSemiAxis(), self.YSemiAxis()); + }, + [](py::tuple t) { // __setstate__ + if (t.size() != 3) + throw std::runtime_error("Invalid state!"); + + return Ellipse2d( + t[0].cast(), + t[1].cast(), + t[2].cast() + ); + } + )) + ; SetupWPyStruct(cls_Ellipse2d); \ No newline at end of file diff --git a/subprojects/robotpy-wpimath/gen/geometry/Pose2d.yml b/subprojects/robotpy-wpimath/gen/geometry/Pose2d.yml index de536214..38d26294 100644 --- a/subprojects/robotpy-wpimath/gen/geometry/Pose2d.yml +++ b/subprojects/robotpy-wpimath/gen/geometry/Pose2d.yml @@ -62,6 +62,22 @@ inline_code: | .def_property_readonly("y_feet", [](Pose2d * self) -> units::foot_t { return self->Y(); }) - .def("__repr__", py::overload_cast(&rpy::toString)); + .def("__repr__", py::overload_cast(&rpy::toString)) + .def(py::pickle( + [](const Pose2d &self) { // __getstate__ + return py::make_tuple(self.X(), self.Y(), self.Rotation().Radians()); + }, + [](py::tuple t) { // __setstate__ + if (t.size() != 3) + throw std::runtime_error("Invalid state!"); + + return Pose2d( + t[0].cast(), + t[1].cast(), + t[2].cast() + ); + } + )) + ; SetupWPyStruct(cls_Pose2d); diff --git a/subprojects/robotpy-wpimath/gen/geometry/Pose3d.yml b/subprojects/robotpy-wpimath/gen/geometry/Pose3d.yml index f8f6a5c4..ef83efd6 100644 --- a/subprojects/robotpy-wpimath/gen/geometry/Pose3d.yml +++ b/subprojects/robotpy-wpimath/gen/geometry/Pose3d.yml @@ -53,6 +53,31 @@ inline_code: | .def_property_readonly("z_feet", [](const Pose3d * self) -> units::foot_t { return self->Z(); }) - .def("__repr__", py::overload_cast(&rpy::toString)); + .def("__repr__", py::overload_cast(&rpy::toString)) + .def(py::pickle( + [](const Pose3d &self) { // __getstate__ + auto q = self.Rotation().GetQuaternion(); + return py::make_tuple(self.X(), self.Y(), self.Z(), q.W(), q.X(), q.Y(), q.Z()); + }, + [](py::tuple t) { // __setstate__ + if (t.size() != 7) + throw std::runtime_error("Invalid state!"); + + return Pose3d( + t[0].cast(), + t[1].cast(), + t[2].cast(), + Rotation3d( + Quaternion( + t[3].cast(), + t[4].cast(), + t[5].cast(), + t[6].cast() + ) + ) + ); + } + )) + ; SetupWPyStruct(cls_Pose3d); diff --git a/subprojects/robotpy-wpimath/gen/geometry/Quaternion.yml b/subprojects/robotpy-wpimath/gen/geometry/Quaternion.yml index 24628276..a6353b19 100644 --- a/subprojects/robotpy-wpimath/gen/geometry/Quaternion.yml +++ b/subprojects/robotpy-wpimath/gen/geometry/Quaternion.yml @@ -48,6 +48,23 @@ classes: inline_code: | cls_Quaternion - .def("__repr__", py::overload_cast(&rpy::toString)); + .def("__repr__", py::overload_cast(&rpy::toString)) + .def(py::pickle( + [](const Quaternion &self) { // __getstate__ + return py::make_tuple(self.W(), self.X(), self.Y(), self.Z()); + }, + [](py::tuple t) { // __setstate__ + if (t.size() != 4) + throw std::runtime_error("Invalid state!"); + + return Quaternion( + t[0].cast(), + t[1].cast(), + t[2].cast(), + t[3].cast() + ); + } + )) + ; SetupWPyStruct(cls_Quaternion); diff --git a/subprojects/robotpy-wpimath/gen/geometry/Rectangle2d.yml b/subprojects/robotpy-wpimath/gen/geometry/Rectangle2d.yml index 56bc9f93..cd756f2e 100644 --- a/subprojects/robotpy-wpimath/gen/geometry/Rectangle2d.yml +++ b/subprojects/robotpy-wpimath/gen/geometry/Rectangle2d.yml @@ -41,7 +41,23 @@ inline_code: | .def_property_readonly("ywidth_feet", [](Rectangle2d &self) -> units::foot_t { return self.YWidth(); }) - .def("__repr__", py::overload_cast(&rpy::toString)); + .def("__repr__", py::overload_cast(&rpy::toString)) + .def(py::pickle( + [](const Rectangle2d &self) { // __getstate__ + return py::make_tuple(self.Center(), self.XWidth(), self.YWidth()); + }, + [](py::tuple t) { // __setstate__ + if (t.size() != 3) + throw std::runtime_error("Invalid state!"); + + return Rectangle2d( + t[0].cast(), + t[1].cast(), + t[2].cast() + ); + } + )) + ; SetupWPyStruct(cls_Rectangle2d); \ No newline at end of file diff --git a/subprojects/robotpy-wpimath/gen/geometry/Rotation2d.yml b/subprojects/robotpy-wpimath/gen/geometry/Rotation2d.yml index 4b3be2fc..aaa53288 100644 --- a/subprojects/robotpy-wpimath/gen/geometry/Rotation2d.yml +++ b/subprojects/robotpy-wpimath/gen/geometry/Rotation2d.yml @@ -51,6 +51,15 @@ inline_code: | .def_static("fromRotations", [](units::turn_t value) { return std::make_unique(value); }) - .def("__repr__", py::overload_cast(&rpy::toString)); + .def("__repr__", py::overload_cast(&rpy::toString)) + .def(py::pickle( + [](const Rotation2d &self) { // __getstate__ + return self.Radians(); + }, + [](units::radian_t t) { // __setstate__ + return Rotation2d(t); + } + )) + ; SetupWPyStruct(cls_Rotation2d); diff --git a/subprojects/robotpy-wpimath/gen/geometry/Rotation3d.yml b/subprojects/robotpy-wpimath/gen/geometry/Rotation3d.yml index d363ba0e..3511debe 100644 --- a/subprojects/robotpy-wpimath/gen/geometry/Rotation3d.yml +++ b/subprojects/robotpy-wpimath/gen/geometry/Rotation3d.yml @@ -60,6 +60,15 @@ inline_code: | .def_property_readonly("angle_degrees", [](const Rotation3d * self) -> units::degree_t { return self->Angle(); }) - .def("__repr__", py::overload_cast(&rpy::toString)); + .def("__repr__", py::overload_cast(&rpy::toString)) + .def(py::pickle( + [](const Rotation3d &self) { // __getstate__ + return self.GetQuaternion(); + }, + [](Quaternion t) { // __setstate__ + return Rotation3d(t); + } + )) + ; SetupWPyStruct(cls_Rotation3d); diff --git a/subprojects/robotpy-wpimath/gen/geometry/Transform2d.yml b/subprojects/robotpy-wpimath/gen/geometry/Transform2d.yml index 900f623b..2c0d98a5 100644 --- a/subprojects/robotpy-wpimath/gen/geometry/Transform2d.yml +++ b/subprojects/robotpy-wpimath/gen/geometry/Transform2d.yml @@ -46,7 +46,22 @@ inline_code: | .def_property_readonly("y_feet", [](Transform2d * self) -> units::foot_t { return self->Y(); }) - .def("__repr__", py::overload_cast(&rpy::toString)); + .def("__repr__", py::overload_cast(&rpy::toString)) + .def(py::pickle( + [](const Transform2d &self) { // __getstate__ + return py::make_tuple(self.X(), self.Y(), self.Rotation().Radians()); + }, + [](py::tuple t) { // __setstate__ + if (t.size() != 3) + throw std::runtime_error("Invalid state!"); + + return Transform2d( + t[0].cast(), + t[1].cast(), + t[2].cast() + ); + } + )) ; SetupWPyStruct(cls_Transform2d); diff --git a/subprojects/robotpy-wpimath/gen/geometry/Transform3d.yml b/subprojects/robotpy-wpimath/gen/geometry/Transform3d.yml index b9692481..89e2371c 100644 --- a/subprojects/robotpy-wpimath/gen/geometry/Transform3d.yml +++ b/subprojects/robotpy-wpimath/gen/geometry/Transform3d.yml @@ -45,6 +45,31 @@ inline_code: | .def_property_readonly("z_feet", [](const Transform3d * self) -> units::foot_t { return self->Z(); }) - .def("__repr__", py::overload_cast(&rpy::toString)); + .def("__repr__", py::overload_cast(&rpy::toString)) + .def(py::pickle( + [](const Transform3d &self) { // __getstate__ + auto q = self.Rotation().GetQuaternion(); + return py::make_tuple(self.X(), self.Y(), self.Z(), q.W(), q.X(), q.Y(), q.Z()); + }, + [](py::tuple t) { // __setstate__ + if (t.size() != 7) + throw std::runtime_error("Invalid state!"); + + return Transform3d( + t[0].cast(), + t[1].cast(), + t[2].cast(), + Rotation3d( + Quaternion( + t[3].cast(), + t[4].cast(), + t[5].cast(), + t[6].cast() + ) + ) + ); + } + )) + ; SetupWPyStruct(cls_Transform3d); diff --git a/subprojects/robotpy-wpimath/gen/geometry/Translation2d.yml b/subprojects/robotpy-wpimath/gen/geometry/Translation2d.yml index 106ae12a..d8ca8407 100644 --- a/subprojects/robotpy-wpimath/gen/geometry/Translation2d.yml +++ b/subprojects/robotpy-wpimath/gen/geometry/Translation2d.yml @@ -80,6 +80,21 @@ inline_code: | throw std::out_of_range("Translation2d index out of range"); } }) - .def("__repr__", py::overload_cast(&rpy::toString)); + .def("__repr__", py::overload_cast(&rpy::toString)) + .def(py::pickle( + [](const Translation2d &self) { // __getstate__ + return py::make_tuple(self.X(), self.Y()); + }, + [](py::tuple t) { // __setstate__ + if (t.size() != 2) + throw std::runtime_error("Invalid state!"); + + return Translation2d( + t[0].cast(), + t[1].cast() + ); + } + )) + ; SetupWPyStruct(cls_Translation2d); diff --git a/subprojects/robotpy-wpimath/gen/geometry/Translation3d.yml b/subprojects/robotpy-wpimath/gen/geometry/Translation3d.yml index a60d7179..27047e2d 100644 --- a/subprojects/robotpy-wpimath/gen/geometry/Translation3d.yml +++ b/subprojects/robotpy-wpimath/gen/geometry/Translation3d.yml @@ -74,6 +74,22 @@ inline_code: | throw std::out_of_range("Translation3d index out of range"); } }) - .def("__repr__", py::overload_cast(&rpy::toString)); + .def("__repr__", py::overload_cast(&rpy::toString)) + .def(py::pickle( + [](const Translation3d &self) { // __getstate__ + return py::make_tuple(self.X(), self.Y(), self.Z()); + }, + [](py::tuple t) { // __setstate__ + if (t.size() != 3) + throw std::runtime_error("Invalid state!"); + + return Translation3d( + t[0].cast(), + t[1].cast(), + t[2].cast() + ); + } + )) + ; SetupWPyStruct(cls_Translation3d); diff --git a/subprojects/robotpy-wpimath/gen/geometry/Twist2d.yml b/subprojects/robotpy-wpimath/gen/geometry/Twist2d.yml index 00f4e628..5aeb1551 100644 --- a/subprojects/robotpy-wpimath/gen/geometry/Twist2d.yml +++ b/subprojects/robotpy-wpimath/gen/geometry/Twist2d.yml @@ -55,6 +55,21 @@ inline_code: | "dy=" + std::to_string(tw.dy()) + ", " "dtheta=" + std::to_string(tw.dtheta()) + ")"; }) + .def(py::pickle( + [](const Twist2d &tw) { // __getstate__ + return py::make_tuple(tw.dx(), tw.dy(), tw.dtheta()); + }, + [](py::tuple t) { // __setstate__ + if (t.size() != 3) + throw std::runtime_error("Invalid state!"); + + return Twist2d( + t[0].cast(), + t[1].cast(), + t[2].cast() + ); + } + )) ; SetupWPyStruct(cls_Twist2d); diff --git a/subprojects/robotpy-wpimath/gen/geometry/Twist3d.yml b/subprojects/robotpy-wpimath/gen/geometry/Twist3d.yml index 82c09de1..cbbc8f6b 100644 --- a/subprojects/robotpy-wpimath/gen/geometry/Twist3d.yml +++ b/subprojects/robotpy-wpimath/gen/geometry/Twist3d.yml @@ -89,6 +89,24 @@ inline_code: | "ry=" + std::to_string(tw.ry()) + ", " "rz=" + std::to_string(tw.rz()) + ")"; }) + .def(py::pickle( + [](const Twist3d &tw) { // __getstate__ + return py::make_tuple(tw.dx(), tw.dy(), tw.dz(), tw.rx(), tw.ry(), tw.rz()); + }, + [](py::tuple t) { // __setstate__ + if (t.size() != 6) + throw std::runtime_error("Invalid state!"); + + return Twist3d( + t[0].cast(), + t[1].cast(), + t[2].cast(), + t[3].cast(), + t[4].cast(), + t[5].cast() + ); + } + )) ; SetupWPyStruct(cls_Twist3d); \ No newline at end of file