mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
[wpimath] Fix TimeInterpolatableBuffer crash (#5972)
Don't decrement buffer iterator if it's at the beginning of the container.
This commit is contained in:
@@ -11,6 +11,26 @@
|
||||
#include "frc/interpolation/TimeInterpolatableBuffer.h"
|
||||
#include "units/time.h"
|
||||
|
||||
TEST(TimeInterpolatableBufferTest, AddSample) {
|
||||
frc::TimeInterpolatableBuffer<frc::Rotation2d> buffer{10_s};
|
||||
|
||||
// No entries
|
||||
buffer.AddSample(1_s, 0_rad);
|
||||
EXPECT_TRUE(buffer.Sample(1_s).value() == 0_rad);
|
||||
|
||||
// New entry at start of container
|
||||
buffer.AddSample(0_s, 1_rad);
|
||||
EXPECT_TRUE(buffer.Sample(0_s).value() == 1_rad);
|
||||
|
||||
// New entry in middle of container
|
||||
buffer.AddSample(0.5_s, 0.5_rad);
|
||||
EXPECT_TRUE(buffer.Sample(0.5_s).value() == 0.5_rad);
|
||||
|
||||
// Override sample
|
||||
buffer.AddSample(0.5_s, 1_rad);
|
||||
EXPECT_TRUE(buffer.Sample(0.5_s).value() == 1_rad);
|
||||
}
|
||||
|
||||
TEST(TimeInterpolatableBufferTest, Interpolation) {
|
||||
frc::TimeInterpolatableBuffer<frc::Rotation2d> buffer{10_s};
|
||||
|
||||
@@ -28,11 +48,14 @@ TEST(TimeInterpolatableBufferTest, Interpolation) {
|
||||
|
||||
TEST(TimeInterpolatableBufferTest, Pose2d) {
|
||||
frc::TimeInterpolatableBuffer<frc::Pose2d> buffer{10_s};
|
||||
|
||||
// We expect to be at (1 - 1/std::sqrt(2), 1/std::sqrt(2), 45deg) at t=0.5
|
||||
buffer.AddSample(0_s, frc::Pose2d{0_m, 0_m, 90_deg});
|
||||
buffer.AddSample(1_s, frc::Pose2d{1_m, 1_m, 0_deg});
|
||||
frc::Pose2d sample = buffer.Sample(0.5_s).value();
|
||||
EXPECT_TRUE(std::abs(sample.X().value() - (1 - 1 / std::sqrt(2))) < 0.01);
|
||||
EXPECT_TRUE(std::abs(sample.Y().value() - (1 / std::sqrt(2))) < 0.01);
|
||||
EXPECT_TRUE(std::abs(sample.Rotation().Degrees().value() - 45) < 0.01);
|
||||
|
||||
EXPECT_TRUE(std::abs(sample.X().value() - (1.0 - 1.0 / std::sqrt(2.0))) <
|
||||
0.01);
|
||||
EXPECT_TRUE(std::abs(sample.Y().value() - (1.0 / std::sqrt(2.0))) < 0.01);
|
||||
EXPECT_TRUE(std::abs(sample.Rotation().Degrees().value() - 45.0) < 0.01);
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user