|
| 1 | +// Copyright (c) TrajoptLib contributors |
| 2 | + |
| 3 | +#include <nanobind/nanobind.h> |
| 4 | +#include <nanobind/operators.h> |
| 5 | +#include <nanobind/stl/string.h> |
| 6 | + |
| 7 | +#include <trajopt/geometry/pose2.hpp> |
| 8 | +#include <trajopt/geometry/rotation2.hpp> |
| 9 | +#include <trajopt/geometry/translation2.hpp> |
| 10 | +#include <trajopt/swerve_trajectory_generator.hpp> |
| 11 | + |
| 12 | +namespace nb = nanobind; |
| 13 | +using namespace nb::literals; |
| 14 | + |
| 15 | +NB_MODULE(trajoptlib_py, m) { |
| 16 | + nb::class_<trajopt::Rotation2d>(m, "Rotation2d") |
| 17 | + .def(nb::init<>()) |
| 18 | + .def(nb::init<double>()) |
| 19 | + .def(nb::init<double, double>()) |
| 20 | + .def(nb::self + nb::self) |
| 21 | + .def(nb::self - nb::self) |
| 22 | + .def(nb::self == nb::self) |
| 23 | + .def(-nb::self) |
| 24 | + .def("rotate_by", |
| 25 | + [](nb::handle_t<trajopt::Rotation2d> self, |
| 26 | + nb::handle_t<trajopt::Rotation2d> other) { |
| 27 | + trajopt::Rotation2d& self_cpp = |
| 28 | + nb::cast<trajopt::Rotation2d&>(self); |
| 29 | + trajopt::Rotation2d& other_cpp = |
| 30 | + nb::cast<trajopt::Rotation2d&>(other); |
| 31 | + return self_cpp.rotate_by(other_cpp); |
| 32 | + }) |
| 33 | + .def("radians", &trajopt::Rotation2d::radians) |
| 34 | + .def("degrees", &trajopt::Rotation2d::degrees) |
| 35 | + .def("cos", &trajopt::Rotation2d::cos) |
| 36 | + .def("sin", &trajopt::Rotation2d::sin); |
| 37 | + |
| 38 | + nb::class_<trajopt::Translation2d>(m, "Translation2d") |
| 39 | + .def(nb::init<>()) |
| 40 | + .def(nb::init<double, double>()) |
| 41 | + .def(nb::init<double, trajopt::Rotation2d>()) |
| 42 | + .def("x", &trajopt::Translation2d::x) |
| 43 | + .def("y", &trajopt::Translation2d::y) |
| 44 | + .def(nb::self + nb::self) |
| 45 | + .def(nb::self - nb::self) |
| 46 | + .def(-nb::self) |
| 47 | + .def(nb::self * double()) |
| 48 | + .def(nb::self / double()) |
| 49 | + .def(nb::self == nb::self) |
| 50 | + .def("rotate_by", |
| 51 | + [](nb::handle_t<trajopt::Translation2d> self, |
| 52 | + nb::handle_t<trajopt::Rotation2d> rotation) { |
| 53 | + trajopt::Translation2d& self_cpp = |
| 54 | + nb::cast<trajopt::Translation2d&>(self); |
| 55 | + trajopt::Rotation2d& rotation_cpp = |
| 56 | + nb::cast<trajopt::Rotation2d&>(rotation); |
| 57 | + return self_cpp.rotate_by(rotation_cpp); |
| 58 | + }) |
| 59 | + .def("angle", &trajopt::Translation2d::angle) |
| 60 | + .def("dot", |
| 61 | + [](nb::handle_t<trajopt::Translation2d> self, |
| 62 | + nb::handle_t<trajopt::Translation2d> other) { |
| 63 | + trajopt::Translation2d& self_cpp = |
| 64 | + nb::cast<trajopt::Translation2d&>(self); |
| 65 | + trajopt::Translation2d& other_cpp = |
| 66 | + nb::cast<trajopt::Translation2d&>(other); |
| 67 | + return self_cpp.dot(other_cpp); |
| 68 | + }) |
| 69 | + .def("cross", |
| 70 | + [](nb::handle_t<trajopt::Translation2d> self, |
| 71 | + nb::handle_t<trajopt::Translation2d> other) { |
| 72 | + trajopt::Translation2d& self_cpp = |
| 73 | + nb::cast<trajopt::Translation2d&>(self); |
| 74 | + trajopt::Translation2d& other_cpp = |
| 75 | + nb::cast<trajopt::Translation2d&>(other); |
| 76 | + return self_cpp.cross(other_cpp); |
| 77 | + }) |
| 78 | + .def("norm", &trajopt::Translation2d::norm) |
| 79 | + .def("squared_norm", &trajopt::Translation2d::squared_norm) |
| 80 | + .def("distance", [](nb::handle_t<trajopt::Translation2d> self, |
| 81 | + nb::handle_t<trajopt::Translation2d> other) { |
| 82 | + trajopt::Translation2d& self_cpp = |
| 83 | + nb::cast<trajopt::Translation2d&>(self); |
| 84 | + trajopt::Translation2d& other_cpp = |
| 85 | + nb::cast<trajopt::Translation2d&>(other); |
| 86 | + return self_cpp.distance(other_cpp); |
| 87 | + }); |
| 88 | + |
| 89 | + nb::class_<trajopt::Pose2d>(m, "Pose2d") |
| 90 | + .def(nb::init<>()) |
| 91 | + .def(nb::init<trajopt::Translation2d, trajopt::Rotation2d>()) |
| 92 | + .def(nb::init<double, double, trajopt::Rotation2d>()) |
| 93 | + .def("translation", &trajopt::Pose2d::translation) |
| 94 | + .def("x", &trajopt::Pose2d::x) |
| 95 | + .def("y", &trajopt::Pose2d::y) |
| 96 | + .def("rotation", &trajopt::Pose2d::rotation) |
| 97 | + .def("rotate_by", [](nb::handle_t<trajopt::Translation2d> self, |
| 98 | + nb::handle_t<trajopt::Rotation2d> rotation) { |
| 99 | + trajopt::Translation2d& self_cpp = |
| 100 | + nb::cast<trajopt::Translation2d&>(self); |
| 101 | + trajopt::Rotation2d& rotation_cpp = |
| 102 | + nb::cast<trajopt::Rotation2d&>(rotation); |
| 103 | + return self_cpp.rotate_by(rotation_cpp); |
| 104 | + }); |
| 105 | +} |
0 commit comments