[py] Fixup new acceleration classes (#8459)

I tried to sync `mostrobotpy` with `allwpilib` and was getting a
compilation error I had not seen before when it tried to do the stub
generation (which `allwpilib` does not do).

Luckily, I was able to debug it here by writing some unit tests (i.e.,
having Gemini convert the C++ tests into python) that failed in a
similar way. The main problem was needing to write a custom constructor
for the class and adding a `force_type_casters`. I used `ChassisSpeed`
as my main example, but I did not copy all of the other custom code like
overriding the index operator, `__repr__` operator, feet helpers, etc. I
can gladly add those in.

In the future, we should start enforce a policy that if you add a C++ or
Java unit test, you also have to add a python test. That developer might
have gotten more stuck on the minutia of how to fix it, but this problem
would have at least been caught earlier before it landed.
This commit is contained in:
PJ Reiniger
2025-12-17 22:19:12 -05:00
committed by GitHub
parent d6b54bbae2
commit a38499dcd7
9 changed files with 551 additions and 0 deletions

View File

@@ -1,5 +1,12 @@
extra_includes:
- wpystruct.h
classes:
wpi::math::ChassisAccelerations:
force_no_default_constructor: true
force_type_casters:
- wpi::units::meters_per_second_squared
- wpi::units::radians_per_second_squared_t
attributes:
ax:
ay:
@@ -15,3 +22,48 @@ classes:
operator*:
operator/:
operator==:
inline_code: |
cls_ChassisAccelerations
.def(
py::init<
wpi::units::meters_per_second_squared_t, wpi::units::meters_per_second_squared_t,
wpi::units::radians_per_second_squared_t
>(),
py::arg("ax") = 0, py::arg("ay") = 0, py::arg("alpha") = 0
)
.def_static("fromFps", [](wpi::units::feet_per_second_squared_t ax, wpi::units::feet_per_second_squared_t ay, wpi::units::radians_per_second_squared_t alpha){
return ChassisAccelerations{ax, ay, alpha};
}, py::arg("ax") = 0, py::arg("ay") = 0, py::arg("alpha") = 0)
.def_property("ax_fpss",
[](ChassisAccelerations * self) -> wpi::units::feet_per_second_squared_t {
return self->ax;
},
[](ChassisAccelerations * self, wpi::units::feet_per_second_squared_t ax) {
self->ax = ax;
}
)
.def_property("ay_fpss",
[](ChassisAccelerations * self) -> wpi::units::feet_per_second_squared_t {
return self->ay;
},
[](ChassisAccelerations * self, wpi::units::feet_per_second_squared_t ay) {
self->ay = ay;
}
)
.def_property("alpha_dpss",
[](ChassisAccelerations * self) -> wpi::units::degrees_per_second_squared_t {
return self->alpha;
},
[](ChassisAccelerations * self, wpi::units::degrees_per_second_squared_t alpha) {
self->alpha = alpha;
}
)
.def("__repr__", [](const ChassisAccelerations &ca) -> std::string {
return "ChassisAccelerations(ax=" + std::to_string(ca.ax()) + ", "
"ay=" + std::to_string(ca.ay()) + ", "
"alpha=" + std::to_string(ca.alpha()) + ")";
})
;
SetupWPyStruct<wpi::math::ChassisAccelerations>(cls_ChassisAccelerations);

View File

@@ -1,5 +1,11 @@
extra_includes:
- wpystruct.h
classes:
wpi::math::DifferentialDriveWheelAccelerations:
force_no_default_constructor: true
force_type_casters:
- wpi::units::meters_per_second_squared
attributes:
left:
right:
@@ -12,3 +18,36 @@ classes:
operator*:
operator/:
operator==:
inline_code: |
cls_DifferentialDriveWheelAccelerations
.def(
py::init<wpi::units::meters_per_second_squared_t, wpi::units::meters_per_second_squared_t>(),
py::arg("left") = 0, py::arg("right") = 0
)
.def_static("fromFps", [](wpi::units::feet_per_second_squared_t left, wpi::units::feet_per_second_squared_t right){
return DifferentialDriveWheelAccelerations{left, right};
}, py::arg("left"), py::arg("right"))
.def_property("left_fpss",
[](DifferentialDriveWheelAccelerations * self) -> wpi::units::feet_per_second_squared_t {
return self->left;
},
[](DifferentialDriveWheelAccelerations * self, wpi::units::feet_per_second_squared_t left) {
self->left = left;
}
)
.def_property("right_fpss",
[](DifferentialDriveWheelAccelerations * self) -> wpi::units::feet_per_second_squared_t {
return self->right;
},
[](DifferentialDriveWheelAccelerations * self, wpi::units::feet_per_second_squared_t right) {
self->right = right;
}
)
.def("__repr__", [](const DifferentialDriveWheelAccelerations &dda) -> std::string {
return "DifferentialDriveWheelAccelerations(left=" + std::to_string(dda.left()) + ", "
"right=" + std::to_string(dda.right()) + ")";
})
;
SetupWPyStruct<wpi::math::DifferentialDriveWheelAccelerations>(cls_DifferentialDriveWheelAccelerations);

View File

@@ -1,5 +1,11 @@
extra_includes:
- wpystruct.h
classes:
wpi::math::MecanumDriveWheelAccelerations:
force_no_default_constructor: true
force_type_casters:
- wpi::units::meters_per_second_squared
attributes:
frontLeft:
frontRight:
@@ -14,3 +20,59 @@ classes:
operator*:
operator/:
operator==:
inline_code: |
cls_MecanumDriveWheelAccelerations
.def(
py::init<
wpi::units::meters_per_second_squared_t, wpi::units::meters_per_second_squared_t, wpi::units::meters_per_second_squared_t, wpi::units::meters_per_second_squared_t
>(),
py::arg("frontLeft") = 0, py::arg("frontRight") = 0, py::arg("rearLeft") = 0, py::arg("rearRight") = 0
)
.def_static("fromFps", [](wpi::units::feet_per_second_squared_t frontLeft,
wpi::units::feet_per_second_squared_t frontRight,
wpi::units::feet_per_second_squared_t rearLeft,
wpi::units::feet_per_second_squared_t rearRight){
return MecanumDriveWheelAccelerations{frontLeft, frontRight, rearLeft, rearRight};
}, py::arg("frontLeft") = 0, py::arg("frontRight") = 0, py::arg("rearLeft") = 0, py::arg("rearRight") = 0)
.def_property("front_left_fpss",
[](MecanumDriveWheelAccelerations * self) -> wpi::units::feet_per_second_squared_t {
return self->frontLeft;
},
[](MecanumDriveWheelAccelerations * self, wpi::units::feet_per_second_squared_t frontLeft) {
self->frontLeft = frontLeft;
}
)
.def_property("front_right_fpss",
[](MecanumDriveWheelAccelerations * self) -> wpi::units::feet_per_second_squared_t {
return self->frontRight;
},
[](MecanumDriveWheelAccelerations * self, wpi::units::feet_per_second_squared_t frontRight) {
self->frontRight = frontRight;
}
)
.def_property("rear_left_fpss",
[](MecanumDriveWheelAccelerations * self) -> wpi::units::feet_per_second_squared_t {
return self->rearLeft;
},
[](MecanumDriveWheelAccelerations * self, wpi::units::feet_per_second_squared_t rearLeft) {
self->rearLeft = rearLeft;
}
)
.def_property("rear_right_fpss",
[](MecanumDriveWheelAccelerations * self) -> wpi::units::feet_per_second_squared_t {
return self->rearRight;
},
[](MecanumDriveWheelAccelerations * self, wpi::units::feet_per_second_squared_t rearRight) {
self->rearRight = rearRight;
}
)
.def("__repr__", [](const MecanumDriveWheelAccelerations &mdwa) -> std::string {
return "MecanumDriveWheelAccelerations(frontLeft=" + std::to_string(mdwa.frontLeft()) + ", "
"frontRight=" + std::to_string(mdwa.frontRight()) + ", "
"rearLeft=" + std::to_string(mdwa.rearLeft()) + ", "
"rearRight=" + std::to_string(mdwa.rearRight()) + ")";
})
;
SetupWPyStruct<wpi::math::MecanumDriveWheelAccelerations>(cls_MecanumDriveWheelAccelerations);

View File

@@ -1,5 +1,11 @@
extra_includes:
- wpystruct.h
classes:
wpi::math::SwerveModuleAcceleration:
force_no_default_constructor: true
force_type_casters:
- wpi::units::meters_per_second_squared
attributes:
acceleration:
angle:
@@ -12,3 +18,30 @@ classes:
'[const]':
operator*:
operator/:
inline_code: |
cls_SwerveModuleAcceleration
.def(
py::init<
wpi::units::meters_per_second_squared_t, wpi::math::Rotation2d
>(),
py::arg("acceleration") = 0, py::arg("angle") = wpi::math::Rotation2d()
)
.def_static("fromFps", [](wpi::units::feet_per_second_squared_t acceleration, wpi::math::Rotation2d angle){
return SwerveModuleAcceleration{acceleration, angle};
}, py::arg("acceleration") = 0, py::arg("angle") = wpi::math::Rotation2d())
.def_property("acceleration_fpss",
[](SwerveModuleAcceleration * self) -> wpi::units::feet_per_second_squared_t {
return self->acceleration;
},
[](SwerveModuleAcceleration * self, wpi::units::feet_per_second_squared_t acceleration) {
self->acceleration = acceleration;
}
)
.def("__repr__", [](const SwerveModuleAcceleration &sma) -> std::string {
return "SwerveModuleAcceleration(acceleration=" + std::to_string(sma.acceleration()) + ", "
"angle=" + std::to_string(sma.angle.Radians()()) + ")";
})
;
SetupWPyStruct<wpi::math::SwerveModuleAcceleration>(cls_SwerveModuleAcceleration);