Class MecanumDrivePoseEstimator3d

java.lang.Object
edu.wpi.first.math.estimator.PoseEstimator3d<MecanumDriveWheelPositions>
edu.wpi.first.math.estimator.MecanumDrivePoseEstimator3d

This class wraps Mecanum Drive Odometry to fuse latency-compensated vision measurements with mecanum drive encoder distance measurements. It will correct for noisy measurements and encoder drift. It is intended to be a drop-in replacement for MecanumDriveOdometry3d. It is also intended to be an easy replacement for MecanumDrivePoseEstimator, only requiring the addition of a standard deviation for Z and appropriate conversions between 2D and 3D versions of geometry classes. (See Pose3d(Pose2d), Rotation3d(Rotation2d), Translation3d(Translation2d), and Pose3d.toPose2d().)

PoseEstimator3d.update(edu.wpi.first.math.geometry.Rotation3d, T) should be called every robot loop.

PoseEstimator3d.addVisionMeasurement(edu.wpi.first.math.geometry.Pose3d, double) can be called as infrequently as you want; if you never call it, then this class will behave mostly like regular encoder odometry.

  • Constructor Details

    • MecanumDrivePoseEstimator3d

      public MecanumDrivePoseEstimator3d(MecanumDriveKinematics kinematics, Rotation3d gyroAngle, MecanumDriveWheelPositions wheelPositions, Pose3d initialPoseMeters)
      Constructs a MecanumDrivePoseEstimator3d with default standard deviations for the model and vision measurements.

      The default standard deviations of the model states are 0.1 meters for x, 0.1 meters for y, 0.1 meters for z, and 0.1 radians for angle. The default standard deviations of the vision measurements are 0.45 meters for x, 0.45 meters for y, 0.45 meters for z, and 0.45 radians for angle.

      Parameters:
      kinematics - A correctly-configured kinematics object for your drivetrain.
      gyroAngle - The current gyro angle.
      wheelPositions - The distances driven by each wheel.
      initialPoseMeters - The starting pose estimate.
    • MecanumDrivePoseEstimator3d

      public MecanumDrivePoseEstimator3d(MecanumDriveKinematics kinematics, Rotation3d gyroAngle, MecanumDriveWheelPositions wheelPositions, Pose3d initialPoseMeters, Matrix<N4,N1> stateStdDevs, Matrix<N4,N1> visionMeasurementStdDevs)
      Constructs a MecanumDrivePoseEstimator3d.
      Parameters:
      kinematics - A correctly-configured kinematics object for your drivetrain.
      gyroAngle - The current gyro angle.
      wheelPositions - The distance measured by each wheel.
      initialPoseMeters - The starting pose estimate.
      stateStdDevs - Standard deviations of the pose estimate (x position in meters, y position in meters, and heading in radians). Increase these numbers to trust your state estimate less.
      visionMeasurementStdDevs - Standard deviations of the vision pose measurement (x position in meters, y position in meters, and heading in radians). Increase these numbers to trust the vision pose measurement less.