From 35e353d91107dd7e7e088cd6b33db89fa4213e00 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Tue, 19 Aug 2025 23:09:17 -0400 Subject: [PATCH] Small fixups --- subprojects/robotpy-wpilib/semiwrap/Color.yml | 2 +- subprojects/robotpy-wpimath/pyproject.toml | 2 ++ .../controls/DifferentialDriveFeedforward.yml | 3 +++ .../robotpy-wpimath/tests/cpp/pyproject.toml | 3 +++ .../tests/cpp/semiwrap/module.yml | 10 ++++--- .../wpimath/controller/__init__.py | 2 ++ .../wpimath/interpolation/__init__.py | 2 +- .../wpimath/kinematics/__init__.py | 26 ++++++++++++++++++- 8 files changed, 44 insertions(+), 6 deletions(-) diff --git a/subprojects/robotpy-wpilib/semiwrap/Color.yml b/subprojects/robotpy-wpilib/semiwrap/Color.yml index 57317be74..450a6016f 100644 --- a/subprojects/robotpy-wpilib/semiwrap/Color.yml +++ b/subprojects/robotpy-wpilib/semiwrap/Color.yml @@ -181,7 +181,7 @@ inline_code: | ^ (std::hash{}(self->green) << 1) ^ (std::hash{}(self->blue) << 2) ); - return h != -1 ? h : -2; + return h != static_cast(-1) ? h : -2; }) .def("__repr__", [](Color *self) { return "Color(" diff --git a/subprojects/robotpy-wpimath/pyproject.toml b/subprojects/robotpy-wpimath/pyproject.toml index 774d63b19..b2e71e2a3 100644 --- a/subprojects/robotpy-wpimath/pyproject.toml +++ b/subprojects/robotpy-wpimath/pyproject.toml @@ -45,6 +45,8 @@ update_init = [ "wpimath.estimator wpimath._controls._controls.estimator", "wpimath.filter", "wpimath.geometry", + "wpimath.kinematics", + "wpimath.interpolation", "wpimath.optimization wpimath._controls._controls.optimization", "wpimath.path wpimath._controls._controls.path", "wpimath.spline", diff --git a/subprojects/robotpy-wpimath/semiwrap/controls/DifferentialDriveFeedforward.yml b/subprojects/robotpy-wpimath/semiwrap/controls/DifferentialDriveFeedforward.yml index 3f26a50ec..ac8a9d1c8 100644 --- a/subprojects/robotpy-wpimath/semiwrap/controls/DifferentialDriveFeedforward.yml +++ b/subprojects/robotpy-wpimath/semiwrap/controls/DifferentialDriveFeedforward.yml @@ -1,3 +1,6 @@ +defaults: + subpackage: controller + classes: frc::DifferentialDriveFeedforward: force_type_casters: diff --git a/subprojects/robotpy-wpimath/tests/cpp/pyproject.toml b/subprojects/robotpy-wpimath/tests/cpp/pyproject.toml index 679f4bdf0..4320ebbe4 100644 --- a/subprojects/robotpy-wpimath/tests/cpp/pyproject.toml +++ b/subprojects/robotpy-wpimath/tests/cpp/pyproject.toml @@ -17,6 +17,9 @@ license = "BSD-3-Clause" [tool.hatch.build.hooks.meson] [tool.semiwrap] +update_init = [ + "wpimath_test wpimath_test._wpimath_test", +] [tool.semiwrap.extension_modules."wpimath_test._wpimath_test"] name = "wpimath_test" diff --git a/subprojects/robotpy-wpimath/tests/cpp/semiwrap/module.yml b/subprojects/robotpy-wpimath/tests/cpp/semiwrap/module.yml index b9157d373..bcec6a22f 100644 --- a/subprojects/robotpy-wpimath/tests/cpp/semiwrap/module.yml +++ b/subprojects/robotpy-wpimath/tests/cpp/semiwrap/module.yml @@ -1,12 +1,13 @@ ---- classes: SomeClass: attributes: - kDefaultPeriod: five_ft: + s_constant: + ms_constant1: + ms_constant2: + ms_constant3: methods: - checkDefaultByName: checkDefaultByNum1: param_override: period: @@ -17,3 +18,6 @@ classes: default: 0.050_s ms2s: ft2m: + checkDefaultByName1: + checkDefaultByName2: + s2ms: diff --git a/subprojects/robotpy-wpimath/wpimath/controller/__init__.py b/subprojects/robotpy-wpimath/wpimath/controller/__init__.py index 4fe1fcdce..eee3b302e 100644 --- a/subprojects/robotpy-wpimath/wpimath/controller/__init__.py +++ b/subprojects/robotpy-wpimath/wpimath/controller/__init__.py @@ -6,6 +6,7 @@ ControlAffinePlantInversionFeedforward_2_1, ControlAffinePlantInversionFeedforward_2_2, DifferentialDriveAccelerationLimiter, + DifferentialDriveFeedforward, DifferentialDriveWheelVoltages, ElevatorFeedforward, HolonomicDriveController, @@ -37,6 +38,7 @@ "ControlAffinePlantInversionFeedforward_2_1", "ControlAffinePlantInversionFeedforward_2_2", "DifferentialDriveAccelerationLimiter", + "DifferentialDriveFeedforward", "DifferentialDriveWheelVoltages", "ElevatorFeedforward", "HolonomicDriveController", diff --git a/subprojects/robotpy-wpimath/wpimath/interpolation/__init__.py b/subprojects/robotpy-wpimath/wpimath/interpolation/__init__.py index c71091b33..8cdd3d6c4 100644 --- a/subprojects/robotpy-wpimath/wpimath/interpolation/__init__.py +++ b/subprojects/robotpy-wpimath/wpimath/interpolation/__init__.py @@ -1,6 +1,6 @@ from . import _init__interpolation # noqa: F401 -# autogenerated by 'robotpy-build create-imports wpimath.interpolation wpimath.interpolation._interpolation' +# autogenerated by 'semiwrap create-imports wpimath.interpolation wpimath.interpolation._interpolation' from ._interpolation import ( TimeInterpolatableFloatBuffer, TimeInterpolatablePose2dBuffer, diff --git a/subprojects/robotpy-wpimath/wpimath/kinematics/__init__.py b/subprojects/robotpy-wpimath/wpimath/kinematics/__init__.py index 4327debb3..f2c7f29aa 100644 --- a/subprojects/robotpy-wpimath/wpimath/kinematics/__init__.py +++ b/subprojects/robotpy-wpimath/wpimath/kinematics/__init__.py @@ -1,35 +1,47 @@ from . import _init__kinematics -# autogenerated by 'robotpy-build create-imports wpimath.kinematics' +# autogenerated by 'semiwrap create-imports wpimath.kinematics wpimath.kinematics._kinematics' from ._kinematics import ( ChassisSpeeds, DifferentialDriveKinematics, DifferentialDriveKinematicsBase, DifferentialDriveOdometry, + DifferentialDriveOdometry3d, + DifferentialDriveOdometry3dBase, DifferentialDriveOdometryBase, DifferentialDriveWheelPositions, DifferentialDriveWheelSpeeds, MecanumDriveKinematics, MecanumDriveKinematicsBase, MecanumDriveOdometry, + MecanumDriveOdometry3d, + MecanumDriveOdometry3dBase, MecanumDriveOdometryBase, MecanumDriveWheelPositions, MecanumDriveWheelSpeeds, SwerveDrive2Kinematics, SwerveDrive2KinematicsBase, SwerveDrive2Odometry, + SwerveDrive2Odometry3d, + SwerveDrive2Odometry3dBase, SwerveDrive2OdometryBase, SwerveDrive3Kinematics, SwerveDrive3KinematicsBase, SwerveDrive3Odometry, + SwerveDrive3Odometry3d, + SwerveDrive3Odometry3dBase, SwerveDrive3OdometryBase, SwerveDrive4Kinematics, SwerveDrive4KinematicsBase, SwerveDrive4Odometry, + SwerveDrive4Odometry3d, + SwerveDrive4Odometry3dBase, SwerveDrive4OdometryBase, SwerveDrive6Kinematics, SwerveDrive6KinematicsBase, SwerveDrive6Odometry, + SwerveDrive6Odometry3d, + SwerveDrive6Odometry3dBase, SwerveDrive6OdometryBase, SwerveModulePosition, SwerveModuleState, @@ -40,30 +52,42 @@ "DifferentialDriveKinematics", "DifferentialDriveKinematicsBase", "DifferentialDriveOdometry", + "DifferentialDriveOdometry3d", + "DifferentialDriveOdometry3dBase", "DifferentialDriveOdometryBase", "DifferentialDriveWheelPositions", "DifferentialDriveWheelSpeeds", "MecanumDriveKinematics", "MecanumDriveKinematicsBase", "MecanumDriveOdometry", + "MecanumDriveOdometry3d", + "MecanumDriveOdometry3dBase", "MecanumDriveOdometryBase", "MecanumDriveWheelPositions", "MecanumDriveWheelSpeeds", "SwerveDrive2Kinematics", "SwerveDrive2KinematicsBase", "SwerveDrive2Odometry", + "SwerveDrive2Odometry3d", + "SwerveDrive2Odometry3dBase", "SwerveDrive2OdometryBase", "SwerveDrive3Kinematics", "SwerveDrive3KinematicsBase", "SwerveDrive3Odometry", + "SwerveDrive3Odometry3d", + "SwerveDrive3Odometry3dBase", "SwerveDrive3OdometryBase", "SwerveDrive4Kinematics", "SwerveDrive4KinematicsBase", "SwerveDrive4Odometry", + "SwerveDrive4Odometry3d", + "SwerveDrive4Odometry3dBase", "SwerveDrive4OdometryBase", "SwerveDrive6Kinematics", "SwerveDrive6KinematicsBase", "SwerveDrive6Odometry", + "SwerveDrive6Odometry3d", + "SwerveDrive6Odometry3dBase", "SwerveDrive6OdometryBase", "SwerveModulePosition", "SwerveModuleState",