mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
[wpimath] Fix C++ pose estimator poseEstimate initialization (#7249)
This commit is contained in:
@@ -359,8 +359,18 @@ TEST(DifferentialDrivePoseEstimatorTest, TestSampleAt) {
|
||||
TEST(DifferentialDrivePoseEstimatorTest, TestReset) {
|
||||
frc::DifferentialDriveKinematics kinematics{1_m};
|
||||
frc::DifferentialDrivePoseEstimator estimator{
|
||||
kinematics, frc::Rotation2d{}, 0_m, 0_m, frc::Pose2d{},
|
||||
{1.0, 1.0, 1.0}, {1.0, 1.0, 1.0}};
|
||||
kinematics,
|
||||
frc::Rotation2d{},
|
||||
0_m,
|
||||
0_m,
|
||||
frc::Pose2d{-1_m, -1_m, frc::Rotation2d{1_rad}},
|
||||
{1.0, 1.0, 1.0},
|
||||
{1.0, 1.0, 1.0}};
|
||||
|
||||
// Test initial pose
|
||||
EXPECT_EQ(-1, estimator.GetEstimatedPosition().X().value());
|
||||
EXPECT_EQ(-1, estimator.GetEstimatedPosition().Y().value());
|
||||
EXPECT_EQ(1, estimator.GetEstimatedPosition().Rotation().Radians().value());
|
||||
|
||||
// Test reset position
|
||||
estimator.ResetPosition(frc::Rotation2d{}, 1_m, 1_m,
|
||||
|
||||
@@ -368,8 +368,17 @@ TEST(MecanumDrivePoseEstimatorTest, TestReset) {
|
||||
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{}, {1.0, 1.0, 1.0}, {1.0, 1.0, 1.0}};
|
||||
kinematics,
|
||||
frc::Rotation2d{},
|
||||
frc::MecanumDriveWheelPositions{},
|
||||
frc::Pose2d{-1_m, -1_m, frc::Rotation2d{1_rad}},
|
||||
{1.0, 1.0, 1.0},
|
||||
{1.0, 1.0, 1.0}};
|
||||
|
||||
// Test initial pose
|
||||
EXPECT_EQ(-1, estimator.GetEstimatedPosition().X().value());
|
||||
EXPECT_EQ(-1, estimator.GetEstimatedPosition().Y().value());
|
||||
EXPECT_EQ(1, estimator.GetEstimatedPosition().Rotation().Radians().value());
|
||||
|
||||
// Test reset position
|
||||
estimator.ResetPosition(frc::Rotation2d{}, {1_m, 1_m, 1_m, 1_m},
|
||||
|
||||
@@ -394,10 +394,15 @@ TEST(SwerveDrivePoseEstimatorTest, TestReset) {
|
||||
frc::Rotation2d{},
|
||||
{frc::SwerveModulePosition{}, frc::SwerveModulePosition{},
|
||||
frc::SwerveModulePosition{}, frc::SwerveModulePosition{}},
|
||||
frc::Pose2d{},
|
||||
frc::Pose2d{-1_m, -1_m, frc::Rotation2d{1_rad}},
|
||||
{1.0, 1.0, 1.0},
|
||||
{1.0, 1.0, 1.0}};
|
||||
|
||||
// Test initial pose
|
||||
EXPECT_EQ(-1, estimator.GetEstimatedPosition().X().value());
|
||||
EXPECT_EQ(-1, estimator.GetEstimatedPosition().Y().value());
|
||||
EXPECT_EQ(1, estimator.GetEstimatedPosition().Rotation().Radians().value());
|
||||
|
||||
// Test reset position
|
||||
{
|
||||
frc::SwerveModulePosition modulePosition{1_m, frc::Rotation2d{}};
|
||||
|
||||
Reference in New Issue
Block a user