mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
[wpimath] Rework function signatures for Pose Estimation / Odometry (#4642)
Forcing the use of SwerveModulePostition[] and wpi::array<SwerveModulePosition, len> in place of variadic function signatures.
This commit is contained in:
@@ -252,7 +252,7 @@ public class SwerveDrivePoseEstimator<States extends Num, Inputs extends Num, Ou
|
||||
* @param modulePositions The current distance measurements and rotations of the swerve modules.
|
||||
*/
|
||||
public void resetPosition(
|
||||
Pose2d poseMeters, Rotation2d gyroAngle, SwerveModulePosition... modulePositions) {
|
||||
Pose2d poseMeters, Rotation2d gyroAngle, SwerveModulePosition[] modulePositions) {
|
||||
// Reset state estimate and error covariance
|
||||
m_observer.reset();
|
||||
m_poseBuffer.clear();
|
||||
|
||||
@@ -65,7 +65,7 @@ public class SwerveDriveOdometry {
|
||||
public SwerveDriveOdometry(
|
||||
SwerveDriveKinematics kinematics,
|
||||
Rotation2d gyroAngle,
|
||||
SwerveModulePosition... modulePositions) {
|
||||
SwerveModulePosition[] modulePositions) {
|
||||
this(kinematics, gyroAngle, modulePositions, new Pose2d());
|
||||
}
|
||||
|
||||
@@ -82,7 +82,7 @@ public class SwerveDriveOdometry {
|
||||
* @param modulePositions The wheel positions reported by each module.
|
||||
*/
|
||||
public void resetPosition(
|
||||
Pose2d pose, Rotation2d gyroAngle, SwerveModulePosition... modulePositions) {
|
||||
Pose2d pose, Rotation2d gyroAngle, SwerveModulePosition[] modulePositions) {
|
||||
if (modulePositions.length != m_numModules) {
|
||||
throw new IllegalArgumentException(
|
||||
"Number of modules is not consistent with number of wheel locations provided in "
|
||||
@@ -120,7 +120,7 @@ public class SwerveDriveOdometry {
|
||||
* in the same order in which you instantiated your SwerveDriveKinematics.
|
||||
* @return The new pose of the robot.
|
||||
*/
|
||||
public Pose2d update(Rotation2d gyroAngle, SwerveModulePosition... modulePositions) {
|
||||
public Pose2d update(Rotation2d gyroAngle, SwerveModulePosition[] modulePositions) {
|
||||
if (modulePositions.length != m_numModules) {
|
||||
throw new IllegalArgumentException(
|
||||
"Number of modules is not consistent with number of wheel locations provided in "
|
||||
|
||||
Reference in New Issue
Block a user