Skip to content

Commit 4e2f83c

Browse files
authored
Fix formatting
1 parent d33cb7a commit 4e2f83c

File tree

4 files changed

+16
-8
lines changed

4 files changed

+16
-8
lines changed

wpimath/src/test/java/edu/wpi/first/math/estimator/SwerveDrivePoseEstimator3dTest.java

Lines changed: 6 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -567,7 +567,9 @@ void testReset() {
567567
() -> assertEquals(0, estimator.getEstimatedPosition().getRotation().getY(), kEpsilon),
568568
() ->
569569
assertEquals(
570-
Math.PI * 3.0 / 4, estimator.getEstimatedPosition().getRotation().getZ(), kEpsilon));
570+
Math.PI * 3.0 / 4,
571+
estimator.getEstimatedPosition().getRotation().getZ(),
572+
kEpsilon));
571573

572574
// Test reset translation
573575
estimator.resetTranslation(new Translation3d(-1, -1, -1));
@@ -580,7 +582,9 @@ void testReset() {
580582
() -> assertEquals(0, estimator.getEstimatedPosition().getRotation().getY(), kEpsilon),
581583
() ->
582584
assertEquals(
583-
Math.PI * 3.0 / 4, estimator.getEstimatedPosition().getRotation().getZ(), kEpsilon));
585+
Math.PI * 3.0 / 4,
586+
estimator.getEstimatedPosition().getRotation().getZ(),
587+
kEpsilon));
584588

585589
// Test reset pose
586590
estimator.resetPose(Pose3d.kZero);

wpimath/src/test/java/edu/wpi/first/math/estimator/SwerveDrivePoseEstimatorTest.java

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -483,7 +483,8 @@ void testReset() {
483483
assertEquals(0, estimator.getEstimatedPosition().getRotation().getRadians(), kEpsilon));
484484

485485
// Add a vision measurement with a different translation
486-
estimator.addVisionMeasurement(new Pose2d(3, 0, Rotation2d.kZero), MathSharedStore.getTimestamp());
486+
estimator.addVisionMeasurement(new Pose2d(3, 0, Rotation2d.kZero),
487+
MathSharedStore.getTimestamp());
487488

488489
assertAll(
489490
() -> assertEquals(2.5, estimator.getEstimatedPosition().getX(), kEpsilon),
@@ -523,7 +524,8 @@ void testReset() {
523524
kEpsilon));
524525

525526
// Add a vision measurement with a different rotation
526-
estimator.addVisionMeasurement(new Pose2d(2.5, 1, Rotation2d.kPi), MathSharedStore.getTimestamp());
527+
estimator.addVisionMeasurement(new Pose2d(2.5, 1, Rotation2d.kPi),
528+
MathSharedStore.getTimestamp());
527529

528530
assertAll(
529531
() -> assertEquals(2.5, estimator.getEstimatedPosition().getX(), kEpsilon),

wpimath/src/test/native/cpp/estimator/SwerveDrivePoseEstimator3dTest.cpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -455,7 +455,7 @@ TEST(SwerveDrivePoseEstimator3dTest, TestReset) {
455455

456456
// Add a vision measurement with a different translation
457457
estimator.AddVisionMeasurement(frc::Pose3d(3_m, 0_m, 0_m, frc::Rotation3d{}),
458-
wpi::math::MathSharedStore::GetTimestamp());
458+
wpi::math::MathSharedStore::GetTimestamp());
459459

460460
EXPECT_DOUBLE_EQ(2.5, estimator.GetEstimatedPosition().X().value());
461461
EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().Y().value());
@@ -491,7 +491,8 @@ TEST(SwerveDrivePoseEstimator3dTest, TestReset) {
491491
estimator.GetEstimatedPosition().Rotation().Z().value());
492492

493493
// Add a vision measurement with a different rotation
494-
estimator.AddVisionMeasurement(frc::Pose3d(2.5_m, 1_m, 0_m, frc::Rotation3d{frc::Rotation2d{180_deg}}),
494+
estimator.AddVisionMeasurement(
495+
frc::Pose3d(2.5_m, 1_m, 0_m, frc::Rotation3d{frc::Rotation2d{180_deg}}),
495496
wpi::math::MathSharedStore::GetTimestamp());
496497

497498
EXPECT_DOUBLE_EQ(2.5, estimator.GetEstimatedPosition().X().value());

wpimath/src/test/native/cpp/estimator/SwerveDrivePoseEstimatorTest.cpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -432,7 +432,7 @@ TEST(SwerveDrivePoseEstimatorTest, TestReset) {
432432

433433
// Add a vision measurement with a different translation
434434
estimator.AddVisionMeasurement(frc::Pose2d{3_m, 0_m, frc::Rotation2d{}},
435-
wpi::math::MathSharedStore::GetTimestamp());
435+
wpi::math::MathSharedStore::GetTimestamp());
436436

437437
EXPECT_DOUBLE_EQ(2.5, estimator.GetEstimatedPosition().X().value());
438438
EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().Y().value());
@@ -462,7 +462,8 @@ TEST(SwerveDrivePoseEstimatorTest, TestReset) {
462462
estimator.GetEstimatedPosition().Rotation().Radians().value());
463463

464464
// Add a vision measurement with a different rotation
465-
estimator.AddVisionMeasurement(frc::Pose2d{2.5_m, 1_m, frc::Rotation2d{180_deg}},
465+
estimator.AddVisionMeasurement(
466+
frc::Pose2d{2.5_m, 1_m, frc::Rotation2d{180_deg}},
466467
wpi::math::MathSharedStore::GetTimestamp());
467468

468469
EXPECT_DOUBLE_EQ(2.5, estimator.GetEstimatedPosition().X().value());

0 commit comments

Comments
 (0)