Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[wpimath] Fix pose estimator reset methods #7225

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -134,6 +134,8 @@ public void resetPosition(Rotation2d gyroAngle, T wheelPositions, Pose2d poseMet
public void resetPose(Pose2d pose) {
m_odometry.resetPose(pose);
m_odometryPoseBuffer.clear();
m_visionUpdates.clear();
m_poseEstimate = m_odometry.getPoseMeters();
}

/**
Expand All @@ -144,6 +146,8 @@ public void resetPose(Pose2d pose) {
public void resetTranslation(Translation2d translation) {
m_odometry.resetTranslation(translation);
m_odometryPoseBuffer.clear();
m_visionUpdates.clear();
m_poseEstimate = m_odometry.getPoseMeters();
}

/**
Expand All @@ -154,6 +158,8 @@ public void resetTranslation(Translation2d translation) {
public void resetRotation(Rotation2d rotation) {
m_odometry.resetRotation(rotation);
m_odometryPoseBuffer.clear();
m_visionUpdates.clear();
m_poseEstimate = m_odometry.getPoseMeters();
}

/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -124,6 +124,8 @@ class WPILIB_DLLEXPORT PoseEstimator {
void ResetPose(const Pose2d& pose) {
m_odometry.ResetPose(pose);
m_odometryPoseBuffer.Clear();
m_visionUpdates.clear();
m_poseEstimate = m_odometry.GetPose();
}

/**
Expand All @@ -134,6 +136,8 @@ class WPILIB_DLLEXPORT PoseEstimator {
void ResetTranslation(const Translation2d& translation) {
m_odometry.ResetTranslation(translation);
m_odometryPoseBuffer.Clear();
m_visionUpdates.clear();
m_poseEstimate = m_odometry.GetPose();
}

/**
Expand All @@ -144,6 +148,8 @@ class WPILIB_DLLEXPORT PoseEstimator {
void ResetRotation(const Rotation2d& rotation) {
m_odometry.ResetRotation(rotation);
m_odometryPoseBuffer.Clear();
m_visionUpdates.clear();
m_poseEstimate = m_odometry.GetPose();
}

/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@

package edu.wpi.first.math.estimator;

import static org.junit.jupiter.api.Assertions.assertAll;
import static org.junit.jupiter.api.Assertions.assertEquals;
import static org.junit.jupiter.api.Assertions.assertTrue;

Expand All @@ -25,6 +26,8 @@
import org.junit.jupiter.api.Test;

class DifferentialDrivePoseEstimatorTest {
private static final double kEpsilon = 1e-9;

@Test
void testAccuracy() {
var kinematics = new DifferentialDriveKinematics(1);
Expand Down Expand Up @@ -355,4 +358,81 @@ void testSampleAt() {
assertEquals(Optional.of(new Pose2d(1, 0.1, Rotation2d.kZero)), estimator.sampleAt(0.5));
assertEquals(Optional.of(new Pose2d(2, 0.1, Rotation2d.kZero)), estimator.sampleAt(2.5));
}

@Test
void testReset() {
var kinematics = new DifferentialDriveKinematics(1);
var estimator =
new DifferentialDrivePoseEstimator(
kinematics,
Rotation2d.kZero,
0,
0,
Pose2d.kZero,
VecBuilder.fill(1, 1, 1),
VecBuilder.fill(1, 1, 1));

// Test reset position
estimator.resetPosition(Rotation2d.kZero, 1, 1, new Pose2d(1, 0, Rotation2d.kZero));

assertAll(
() -> assertEquals(1, estimator.getEstimatedPosition().getX(), kEpsilon),
() -> assertEquals(0, estimator.getEstimatedPosition().getY(), kEpsilon),
() ->
assertEquals(0, estimator.getEstimatedPosition().getRotation().getRadians(), kEpsilon));

// Test orientation and wheel positions
estimator.update(Rotation2d.kZero, 2, 2);

assertAll(
() -> assertEquals(2, estimator.getEstimatedPosition().getX(), kEpsilon),
() -> assertEquals(0, estimator.getEstimatedPosition().getY(), kEpsilon),
() ->
assertEquals(0, estimator.getEstimatedPosition().getRotation().getRadians(), kEpsilon));

// Test reset rotation
estimator.resetRotation(Rotation2d.kCCW_Pi_2);

assertAll(
() -> assertEquals(2, estimator.getEstimatedPosition().getX(), kEpsilon),
() -> assertEquals(0, estimator.getEstimatedPosition().getY(), kEpsilon),
() ->
assertEquals(
Math.PI / 2,
estimator.getEstimatedPosition().getRotation().getRadians(),
kEpsilon));

// Test orientation
estimator.update(Rotation2d.kZero, 3, 3);

assertAll(
() -> assertEquals(2, estimator.getEstimatedPosition().getX(), kEpsilon),
() -> assertEquals(1, estimator.getEstimatedPosition().getY(), kEpsilon),
() ->
assertEquals(
Math.PI / 2,
estimator.getEstimatedPosition().getRotation().getRadians(),
kEpsilon));

// Test reset translation
estimator.resetTranslation(new Translation2d(-1, -1));

assertAll(
() -> assertEquals(-1, estimator.getEstimatedPosition().getX(), kEpsilon),
() -> assertEquals(-1, estimator.getEstimatedPosition().getY(), kEpsilon),
() ->
assertEquals(
Math.PI / 2,
estimator.getEstimatedPosition().getRotation().getRadians(),
kEpsilon));

// Test reset pose
estimator.resetPose(Pose2d.kZero);

assertAll(
() -> assertEquals(0, estimator.getEstimatedPosition().getX(), kEpsilon),
() -> assertEquals(0, estimator.getEstimatedPosition().getY(), kEpsilon),
() ->
assertEquals(0, estimator.getEstimatedPosition().getRotation().getRadians(), kEpsilon));
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@

package edu.wpi.first.math.estimator;

import static org.junit.jupiter.api.Assertions.assertAll;
import static org.junit.jupiter.api.Assertions.assertEquals;
import static org.junit.jupiter.api.Assertions.assertTrue;

Expand All @@ -26,6 +27,8 @@
import org.junit.jupiter.api.Test;

class MecanumDrivePoseEstimatorTest {
private static final double kEpsilon = 1e-9;

@Test
void testAccuracyFacingTrajectory() {
var kinematics =
Expand Down Expand Up @@ -377,4 +380,88 @@ void testSampleAt() {
assertEquals(Optional.of(new Pose2d(1, 0.1, Rotation2d.kZero)), estimator.sampleAt(0.5));
assertEquals(Optional.of(new Pose2d(2, 0.1, Rotation2d.kZero)), estimator.sampleAt(2.5));
}

@Test
void testReset() {
var kinematics =
new MecanumDriveKinematics(
new Translation2d(1, 1),
new Translation2d(-1, 1),
new Translation2d(1, -1),
new Translation2d(-1, -1));
var estimator =
new MecanumDrivePoseEstimator(
kinematics,
Rotation2d.kZero,
new MecanumDriveWheelPositions(),
Pose2d.kZero,
VecBuilder.fill(1, 1, 1),
VecBuilder.fill(1, 1, 1));

// Test reset position
estimator.resetPosition(
Rotation2d.kZero,
new MecanumDriveWheelPositions(1, 1, 1, 1),
new Pose2d(1, 0, Rotation2d.kZero));

assertAll(
() -> assertEquals(1, estimator.getEstimatedPosition().getX(), kEpsilon),
() -> assertEquals(0, estimator.getEstimatedPosition().getY(), kEpsilon),
() ->
assertEquals(0, estimator.getEstimatedPosition().getRotation().getRadians(), kEpsilon));

// Test orientation and wheel positions
estimator.update(Rotation2d.kZero, new MecanumDriveWheelPositions(2, 2, 2, 2));

assertAll(
() -> assertEquals(2, estimator.getEstimatedPosition().getX(), kEpsilon),
() -> assertEquals(0, estimator.getEstimatedPosition().getY(), kEpsilon),
() ->
assertEquals(0, estimator.getEstimatedPosition().getRotation().getRadians(), kEpsilon));

// Test reset rotation
estimator.resetRotation(Rotation2d.kCCW_Pi_2);

assertAll(
() -> assertEquals(2, estimator.getEstimatedPosition().getX(), kEpsilon),
() -> assertEquals(0, estimator.getEstimatedPosition().getY(), kEpsilon),
() ->
assertEquals(
Math.PI / 2,
estimator.getEstimatedPosition().getRotation().getRadians(),
kEpsilon));

// Test orientation
estimator.update(Rotation2d.kZero, new MecanumDriveWheelPositions(3, 3, 3, 3));

assertAll(
() -> assertEquals(2, estimator.getEstimatedPosition().getX(), kEpsilon),
() -> assertEquals(1, estimator.getEstimatedPosition().getY(), kEpsilon),
() ->
assertEquals(
Math.PI / 2,
estimator.getEstimatedPosition().getRotation().getRadians(),
kEpsilon));

// Test reset translation
estimator.resetTranslation(new Translation2d(-1, -1));

assertAll(
() -> assertEquals(-1, estimator.getEstimatedPosition().getX(), kEpsilon),
() -> assertEquals(-1, estimator.getEstimatedPosition().getY(), kEpsilon),
() ->
assertEquals(
Math.PI / 2,
estimator.getEstimatedPosition().getRotation().getRadians(),
kEpsilon));

// Test reset pose
estimator.resetPose(Pose2d.kZero);

assertAll(
() -> assertEquals(0, estimator.getEstimatedPosition().getX(), kEpsilon),
() -> assertEquals(0, estimator.getEstimatedPosition().getY(), kEpsilon),
() ->
assertEquals(0, estimator.getEstimatedPosition().getRotation().getRadians(), kEpsilon));
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@

package edu.wpi.first.math.estimator;

import static org.junit.jupiter.api.Assertions.assertAll;
import static org.junit.jupiter.api.Assertions.assertEquals;
import static org.junit.jupiter.api.Assertions.assertTrue;

Expand All @@ -26,6 +27,8 @@
import org.junit.jupiter.api.Test;

class SwerveDrivePoseEstimatorTest {
private static final double kEpsilon = 1e-9;

@Test
void testAccuracyFacingTrajectory() {
var kinematics =
Expand Down Expand Up @@ -422,4 +425,112 @@ void testSampleAt() {
assertEquals(Optional.of(new Pose2d(1, 0.1, Rotation2d.kZero)), estimator.sampleAt(0.5));
assertEquals(Optional.of(new Pose2d(2, 0.1, Rotation2d.kZero)), estimator.sampleAt(2.5));
}

@Test
void testReset() {
var kinematics =
new SwerveDriveKinematics(
new Translation2d(1, 1),
new Translation2d(-1, 1),
new Translation2d(1, -1),
new Translation2d(-1, -1));
var estimator =
new SwerveDrivePoseEstimator(
kinematics,
Rotation2d.kZero,
new SwerveModulePosition[] {
new SwerveModulePosition(),
new SwerveModulePosition(),
new SwerveModulePosition(),
new SwerveModulePosition()
},
Pose2d.kZero,
VecBuilder.fill(1, 1, 1),
VecBuilder.fill(1, 1, 1));

// Test reset position
{
var modulePosition = new SwerveModulePosition(1, Rotation2d.kZero);
estimator.resetPosition(
Rotation2d.kZero,
new SwerveModulePosition[] {
modulePosition, modulePosition, modulePosition, modulePosition
},
new Pose2d(1, 0, Rotation2d.kZero));
}

assertAll(
() -> assertEquals(1, estimator.getEstimatedPosition().getX(), kEpsilon),
() -> assertEquals(0, estimator.getEstimatedPosition().getY(), kEpsilon),
() ->
assertEquals(0, estimator.getEstimatedPosition().getRotation().getRadians(), kEpsilon));

// Test orientation and wheel positions
{
var modulePosition = new SwerveModulePosition(2, Rotation2d.kZero);
estimator.update(
Rotation2d.kZero,
new SwerveModulePosition[] {
modulePosition, modulePosition, modulePosition, modulePosition
});
}

assertAll(
() -> assertEquals(2, estimator.getEstimatedPosition().getX(), kEpsilon),
() -> assertEquals(0, estimator.getEstimatedPosition().getY(), kEpsilon),
() ->
assertEquals(0, estimator.getEstimatedPosition().getRotation().getRadians(), kEpsilon));

// Test reset rotation
estimator.resetRotation(Rotation2d.kCCW_Pi_2);

assertAll(
() -> assertEquals(2, estimator.getEstimatedPosition().getX(), kEpsilon),
() -> assertEquals(0, estimator.getEstimatedPosition().getY(), kEpsilon),
() ->
assertEquals(
Math.PI / 2,
estimator.getEstimatedPosition().getRotation().getRadians(),
kEpsilon));

// Test orientation
{
var modulePosition = new SwerveModulePosition(3, Rotation2d.kZero);
estimator.update(
Rotation2d.kZero,
new SwerveModulePosition[] {
modulePosition, modulePosition, modulePosition, modulePosition
});
}

assertAll(
() -> assertEquals(2, estimator.getEstimatedPosition().getX(), kEpsilon),
() -> assertEquals(1, estimator.getEstimatedPosition().getY(), kEpsilon),
() ->
assertEquals(
Math.PI / 2,
estimator.getEstimatedPosition().getRotation().getRadians(),
kEpsilon));

// Test reset translation
estimator.resetTranslation(new Translation2d(-1, -1));

assertAll(
() -> assertEquals(-1, estimator.getEstimatedPosition().getX(), kEpsilon),
() -> assertEquals(-1, estimator.getEstimatedPosition().getY(), kEpsilon),
() ->
assertEquals(
Math.PI / 2,
estimator.getEstimatedPosition().getRotation().getRadians(),
kEpsilon));

// Test reset pose
estimator.resetPose(Pose2d.kZero);

assertAll(
() -> assertEquals(0, estimator.getEstimatedPosition().getX(), kEpsilon),
() -> assertEquals(0, estimator.getEstimatedPosition().getY(), kEpsilon),
() ->
assertEquals(0, estimator.getEstimatedPosition().getRotation().getRadians(), kEpsilon));
}
}
Loading
Loading