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

Discard stale pose estimates #5045

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
23 commits
Select commit Hold shift + click to select a range
85772ec
discard stale vision measurements, java
jlmcmchl Feb 4, 2023
5f2f092
discard stale vision measurement, cpp
jlmcmchl Feb 4, 2023
4d8c897
Update wpimath/src/main/native/include/frc/estimator/MecanumDrivePose…
calcmogul Feb 4, 2023
fc5802e
Update wpimath/src/main/native/include/frc/estimator/DifferentialDriv…
calcmogul Feb 4, 2023
1cdf510
Update wpimath/src/main/native/include/frc/estimator/MecanumDrivePose…
calcmogul Feb 4, 2023
6c964a7
Update wpimath/src/main/native/include/frc/estimator/SwerveDrivePoseE…
calcmogul Feb 4, 2023
734af06
Update wpimath/src/main/native/include/frc/estimator/SwerveDrivePoseE…
calcmogul Feb 4, 2023
4607d92
Update wpimath/src/test/java/edu/wpi/first/math/estimator/SwerveDrive…
calcmogul Feb 4, 2023
cab2b94
Update wpimath/src/main/native/cpp/estimator/DifferentialDrivePoseEst…
calcmogul Feb 4, 2023
3d19f18
Update wpimath/src/main/native/cpp/estimator/MecanumDrivePoseEstimato…
calcmogul Feb 4, 2023
c595302
Update wpimath/src/main/native/include/frc/estimator/DifferentialDriv…
calcmogul Feb 4, 2023
744f794
Update wpimath/src/main/native/include/frc/estimator/SwerveDrivePoseE…
calcmogul Feb 4, 2023
72fc2a0
Update wpimath/src/main/java/edu/wpi/first/math/estimator/Differentia…
calcmogul Feb 4, 2023
60b11f5
Update wpimath/src/main/java/edu/wpi/first/math/estimator/Differentia…
calcmogul Feb 4, 2023
f7692db
Update wpimath/src/main/java/edu/wpi/first/math/estimator/Differentia…
calcmogul Feb 4, 2023
b3f1a21
Update wpimath/src/main/java/edu/wpi/first/math/estimator/MecanumDriv…
calcmogul Feb 4, 2023
c9b3e54
Update wpimath/src/main/java/edu/wpi/first/math/estimator/MecanumDriv…
calcmogul Feb 4, 2023
f345310
Update wpimath/src/main/java/edu/wpi/first/math/estimator/SwerveDrive…
calcmogul Feb 4, 2023
782ff01
Update wpimath/src/main/java/edu/wpi/first/math/estimator/SwerveDrive…
calcmogul Feb 4, 2023
2d51895
Update wpimath/src/main/java/edu/wpi/first/math/estimator/SwerveDrive…
calcmogul Feb 4, 2023
e938524
Update wpimath/src/test/java/edu/wpi/first/math/estimator/MecanumDriv…
calcmogul Feb 4, 2023
b9b04ef
Run wpiformat
calcmogul Feb 4, 2023
ed8b32c
Fix compilation error
calcmogul Feb 4, 2023
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 @@ -40,8 +40,10 @@ public class DifferentialDrivePoseEstimator {
private final Matrix<N3, N1> m_q = new Matrix<>(Nat.N3(), Nat.N1());
private Matrix<N3, N3> m_visionK = new Matrix<>(Nat.N3(), Nat.N3());

private static final double kBufferDuration = 1.5;

private final TimeInterpolatableBuffer<InterpolationRecord> m_poseBuffer =
TimeInterpolatableBuffer.createBuffer(1.5);
TimeInterpolatableBuffer.createBuffer(kBufferDuration);

/**
* Constructs a DifferentialDrivePoseEstimator with default standard deviations for the model and
Expand Down Expand Up @@ -187,6 +189,11 @@ public Pose2d getEstimatedPosition() {
* or sync the epochs.
*/
public void addVisionMeasurement(Pose2d visionRobotPoseMeters, double timestampSeconds) {
// Step 0: If this measurement is old enough to be outside the pose buffer's timespan, skip.
if (m_poseBuffer.getInternalBuffer().lastKey() - kBufferDuration > timestampSeconds) {
return;
}

// Step 1: Get the pose odometry measured at the moment the vision measurement was made.
var sample = m_poseBuffer.getSample(timestampSeconds);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,8 +39,10 @@ public class MecanumDrivePoseEstimator {
private final Matrix<N3, N1> m_q = new Matrix<>(Nat.N3(), Nat.N1());
private Matrix<N3, N3> m_visionK = new Matrix<>(Nat.N3(), Nat.N3());

private static final double kBufferDuration = 1.5;

private final TimeInterpolatableBuffer<InterpolationRecord> m_poseBuffer =
TimeInterpolatableBuffer.createBuffer(1.5);
TimeInterpolatableBuffer.createBuffer(kBufferDuration);

/**
* Constructs a MecanumDrivePoseEstimator with default standard deviations for the model and
Expand Down Expand Up @@ -175,6 +177,11 @@ public Pose2d getEstimatedPosition() {
* your time source or sync the epochs.
*/
public void addVisionMeasurement(Pose2d visionRobotPoseMeters, double timestampSeconds) {
// Step 0: If this measurement is old enough to be outside the pose buffer's timespan, skip.
if (m_poseBuffer.getInternalBuffer().lastKey() - kBufferDuration > timestampSeconds) {
return;
}

// Step 1: Get the pose odometry measured at the moment the vision measurement was made.
var sample = m_poseBuffer.getSample(timestampSeconds);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,8 +40,10 @@ public class SwerveDrivePoseEstimator {
private final int m_numModules;
private Matrix<N3, N3> m_visionK = new Matrix<>(Nat.N3(), Nat.N3());

private static final double kBufferDuration = 1.5;

private final TimeInterpolatableBuffer<InterpolationRecord> m_poseBuffer =
TimeInterpolatableBuffer.createBuffer(1.5);
TimeInterpolatableBuffer.createBuffer(kBufferDuration);

/**
* Constructs a SwerveDrivePoseEstimator with default standard deviations for the model and vision
Expand Down Expand Up @@ -177,6 +179,11 @@ public Pose2d getEstimatedPosition() {
* or sync the epochs.
*/
public void addVisionMeasurement(Pose2d visionRobotPoseMeters, double timestampSeconds) {
// Step 0: If this measurement is old enough to be outside the pose buffer's timespan, skip.
if (m_poseBuffer.getInternalBuffer().lastKey() - kBufferDuration > timestampSeconds) {
return;
}

// Step 1: Get the pose odometry measured at the moment the vision measurement was made.
var sample = m_poseBuffer.getSample(timestampSeconds);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -94,6 +94,13 @@ Pose2d DifferentialDrivePoseEstimator::GetEstimatedPosition() const {

void DifferentialDrivePoseEstimator::AddVisionMeasurement(
const Pose2d& visionRobotPose, units::second_t timestamp) {
// Step 0: If this measurement is old enough to be outside the pose buffer's
// timespan, skip.
if (m_poseBuffer.GetInternalBuffer().front().first - kBufferDuration >
timestamp) {
return;
}

// Step 1: Get the estimated pose from when the vision measurement was made.
auto sample = m_poseBuffer.Sample(timestamp);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -105,6 +105,13 @@ Pose2d frc::MecanumDrivePoseEstimator::GetEstimatedPosition() const {

void frc::MecanumDrivePoseEstimator::AddVisionMeasurement(
const Pose2d& visionRobotPose, units::second_t timestamp) {
// Step 0: If this measurement is old enough to be outside the pose buffer's
// timespan, skip.
if (m_poseBuffer.GetInternalBuffer().front().first - kBufferDuration >
timestamp) {
return;
}

// Step 1: Get the estimated pose from when the vision measurement was made.
auto sample = m_poseBuffer.Sample(timestamp);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -240,14 +240,16 @@ class WPILIB_DLLEXPORT DifferentialDrivePoseEstimator {
double i) const;
};

static constexpr units::second_t kBufferDuration = 1.5_s;

DifferentialDriveKinematics& m_kinematics;
DifferentialDriveOdometry m_odometry;
wpi::array<double, 3> m_q{wpi::empty_array};
Eigen::Matrix3d m_visionK = Eigen::Matrix3d::Zero();

TimeInterpolatableBuffer<InterpolationRecord> m_poseBuffer{
1.5_s, [this](const InterpolationRecord& start,
const InterpolationRecord& end, double t) {
kBufferDuration, [this](const InterpolationRecord& start,
const InterpolationRecord& end, double t) {
return start.Interpolate(this->m_kinematics, end, t);
}};
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -232,14 +232,16 @@ class WPILIB_DLLEXPORT MecanumDrivePoseEstimator {
double i) const;
};

static constexpr units::second_t kBufferDuration = 1.5_s;

MecanumDriveKinematics& m_kinematics;
MecanumDriveOdometry m_odometry;
wpi::array<double, 3> m_q{wpi::empty_array};
Eigen::Matrix3d m_visionK = Eigen::Matrix3d::Zero();

TimeInterpolatableBuffer<InterpolationRecord> m_poseBuffer{
1.5_s, [this](const InterpolationRecord& start,
const InterpolationRecord& end, double t) {
kBufferDuration, [this](const InterpolationRecord& start,
const InterpolationRecord& end, double t) {
return start.Interpolate(this->m_kinematics, end, t);
}};
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -170,6 +170,13 @@ class SwerveDrivePoseEstimator {
*/
void AddVisionMeasurement(const Pose2d& visionRobotPose,
units::second_t timestamp) {
// Step 0: If this measurement is old enough to be outside the pose buffer's
// timespan, skip.
if (m_poseBuffer.GetInternalBuffer().front().first - kBufferDuration >
timestamp) {
return;
}

// Step 1: Get the estimated pose from when the vision measurement was made.
auto sample = m_poseBuffer.Sample(timestamp);

Expand Down Expand Up @@ -374,14 +381,16 @@ class SwerveDrivePoseEstimator {
}
};

static constexpr units::second_t kBufferDuration = 1.5_s;

SwerveDriveKinematics<NumModules>& m_kinematics;
SwerveDriveOdometry<NumModules> m_odometry;
wpi::array<double, 3> m_q{wpi::empty_array};
Eigen::Matrix3d m_visionK = Eigen::Matrix3d::Zero();

TimeInterpolatableBuffer<InterpolationRecord> m_poseBuffer{
1.5_s, [this](const InterpolationRecord& start,
const InterpolationRecord& end, double t) {
kBufferDuration, [this](const InterpolationRecord& start,
const InterpolationRecord& end, double t) {
return start.Interpolate(this->m_kinematics, end, t);
}};
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -266,4 +266,41 @@ void testSimultaneousVisionMeasurements() {
assertEquals(dx > 0.08 || dy > 0.08 || dtheta > 0.08, true, errorLog);
}
}

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

double time = 0;

// Add enough measurements to fill up the buffer
for (; time < 4; time += 0.02) {
estimator.updateWithTime(time, new Rotation2d(), 0, 0);
}

var odometryPose = estimator.getEstimatedPosition();

// Apply a vision measurement made 3 seconds ago
// This test passes if this does not cause a ConcurrentModificationException.
estimator.addVisionMeasurement(
new Pose2d(new Translation2d(10, 10), new Rotation2d(0.1)),
1,
VecBuilder.fill(0.1, 0.1, 0.1));

assertEquals(odometryPose.getX(), estimator.getEstimatedPosition().getX(), "Incorrect Final X");
assertEquals(odometryPose.getY(), estimator.getEstimatedPosition().getY(), "Incorrect Final Y");
assertEquals(
odometryPose.getRotation().getRadians(),
estimator.getEstimatedPosition().getRotation().getRadians(),
"Incorrect Final Theta");
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -279,4 +279,45 @@ void testSimultaneousVisionMeasurements() {
assertEquals(dx > 0.08 || dy > 0.08 || dtheta > 0.08, true, errorLog);
}
}

@Test
void testDiscardsOldVisionMeasurements() {
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,
new Rotation2d(),
new MecanumDriveWheelPositions(),
new Pose2d(),
VecBuilder.fill(0.1, 0.1, 0.1),
VecBuilder.fill(0.9, 0.9, 0.9));

double time = 0;

// Add enough measurements to fill up the buffer
for (; time < 4; time += 0.02) {
estimator.updateWithTime(time, new Rotation2d(), new MecanumDriveWheelPositions());
}

var odometryPose = estimator.getEstimatedPosition();

// Apply a vision measurement made 3 seconds ago
// This test passes if this does not cause a ConcurrentModificationException.
estimator.addVisionMeasurement(
new Pose2d(new Translation2d(10, 10), new Rotation2d(0.1)),
1,
VecBuilder.fill(0.1, 0.1, 0.1));

assertEquals(odometryPose.getX(), estimator.getEstimatedPosition().getX(), "Incorrect Final X");
assertEquals(odometryPose.getY(), estimator.getEstimatedPosition().getY(), "Incorrect Final Y");
assertEquals(
odometryPose.getRotation().getRadians(),
estimator.getEstimatedPosition().getRotation().getRadians(),
"Incorrect Final Theta");
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -300,4 +300,58 @@ void testSimultaneousVisionMeasurements() {
assertEquals(dx > 0.08 || dy > 0.08 || dtheta > 0.08, true, errorLog);
}
}

@Test
void testDiscardsOldVisionMeasurements() {
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,
new Rotation2d(),
new SwerveModulePosition[] {
new SwerveModulePosition(),
new SwerveModulePosition(),
new SwerveModulePosition(),
new SwerveModulePosition()
},
new Pose2d(),
VecBuilder.fill(0.1, 0.1, 0.1),
VecBuilder.fill(0.9, 0.9, 0.9));

double time = 0;

// Add enough measurements to fill up the buffer
for (; time < 4; time += 0.02) {
estimator.updateWithTime(
time,
new Rotation2d(),
new SwerveModulePosition[] {
new SwerveModulePosition(),
new SwerveModulePosition(),
new SwerveModulePosition(),
new SwerveModulePosition()
});
}

var odometryPose = estimator.getEstimatedPosition();

// Apply a vision measurement made 3 seconds ago
// This test passes if this does not cause a ConcurrentModificationException.
estimator.addVisionMeasurement(
new Pose2d(new Translation2d(10, 10), new Rotation2d(0.1)),
1,
VecBuilder.fill(0.1, 0.1, 0.1));

assertEquals(odometryPose.getX(), estimator.getEstimatedPosition().getX(), "Incorrect Final X");
assertEquals(odometryPose.getY(), estimator.getEstimatedPosition().getY(), "Incorrect Final Y");
assertEquals(
odometryPose.getRotation().getRadians(),
estimator.getEstimatedPosition().getRotation().getRadians(),
"Incorrect Final Theta");
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -263,3 +263,31 @@ TEST(DifferentialDrivePoseEstimatorTest, SimultaneousVisionMeasurements) {
EXPECT_TRUE(dx > 0.08_m || dy > 0.08_m || dtheta > 0.08_rad);
}
}

TEST(DifferentialDrivePoseEstimatorTest, TestDiscardStaleVisionMeasurements) {
frc::DifferentialDriveKinematics kinematics{1_m};

frc::DifferentialDrivePoseEstimator estimator{
kinematics, frc::Rotation2d{}, 0_m, 0_m, frc::Pose2d{},
{0.1, 0.1, 0.1}, {0.45, 0.45, 0.45}};

// Add enough measurements to fill up the bufer
for (auto time = 0.0_s; time < 4_s; time += 0.02_s) {
estimator.UpdateWithTime(time, frc::Rotation2d{}, 0_m, 0_m);
}

auto odometryPose = estimator.GetEstimatedPosition();

// Apply a vision measurement from 3 seconds ago
estimator.AddVisionMeasurement(
frc::Pose2d{frc::Translation2d{10_m, 10_m}, frc::Rotation2d{0.1_rad}},
1_s, {0.1, 0.1, 0.1});

EXPECT_NEAR(odometryPose.X().value(),
estimator.GetEstimatedPosition().X().value(), 1e-6);
EXPECT_NEAR(odometryPose.Y().value(),
estimator.GetEstimatedPosition().Y().value(), 1e-6);
EXPECT_NEAR(odometryPose.Rotation().Radians().value(),
estimator.GetEstimatedPosition().Rotation().Radians().value(),
1e-6);
}
Original file line number Diff line number Diff line change
Expand Up @@ -262,3 +262,34 @@ TEST(MecanumDrivePoseEstimatorTest, SimultaneousVisionMeasurements) {
EXPECT_TRUE(dx > 0.08_m || dy > 0.08_m || dtheta > 0.08_rad);
}
}

TEST(MecanumDrivePoseEstimatorTest, TestDiscardStaleVisionMeasurements) {
frc::MecanumDriveKinematics kinematics{
frc::Translation2d{1_m, 1_m}, frc::Translation2d{1_m, -1_m},
frc::Translation2d{-1_m, -1_m}, frc::Translation2d{-1_m, 1_m}};

frc::MecanumDrivePoseEstimator estimator{
kinematics, frc::Rotation2d{}, frc::MecanumDriveWheelPositions{},
frc::Pose2d{}, {0.1, 0.1, 0.1}, {0.45, 0.45, 0.45}};

// Add enough measurements to fill up the bufer
for (auto time = 0.0_s; time < 4_s; time += 0.02_s) {
estimator.UpdateWithTime(time, frc::Rotation2d{},
frc::MecanumDriveWheelPositions{});
}

auto odometryPose = estimator.GetEstimatedPosition();

// Apply a vision measurement from 3 seconds ago
estimator.AddVisionMeasurement(
frc::Pose2d{frc::Translation2d{10_m, 10_m}, frc::Rotation2d{0.1_rad}},
1_s, {0.1, 0.1, 0.1});

EXPECT_NEAR(odometryPose.X().value(),
estimator.GetEstimatedPosition().X().value(), 1e-6);
EXPECT_NEAR(odometryPose.Y().value(),
estimator.GetEstimatedPosition().Y().value(), 1e-6);
EXPECT_NEAR(odometryPose.Rotation().Radians().value(),
estimator.GetEstimatedPosition().Rotation().Radians().value(),
1e-6);
}
Loading