MecanumDrivePoseEstimator3d

class wpimath.MecanumDrivePoseEstimator3d(*args, **kwargs)

Bases: MecanumDrivePoseEstimator3dBase

This class wraps Mecanum Drive Odometry to fuse latency-compensated vision measurements with mecanum drive encoder velocity measurements. It will correct for noisy measurements and encoder drift. It is intended to be an easy drop-in for MecanumDriveOdometry3d. It is also intended to be an easy replacement for PoseEstimator, 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().)

Update() should be called every robot loop. If your loops are faster or slower than the default of 20 ms, then you should change the nominal delta time by specifying it in the constructor.

AddVisionMeasurement() can be called as infrequently as you want; if you never call it, then this class will behave mostly like regular encoder odometry.

Overloaded function.

  1. __init__(self: wpimath._wpimath.MecanumDrivePoseEstimator3d, kinematics: wpimath._wpimath.MecanumDriveKinematics, gyroAngle: wpimath._wpimath.Rotation3d, wheelPositions: wpimath._wpimath.MecanumDriveWheelPositions, initialPose: wpimath._wpimath.Pose3d) -> None

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 distance measured by each wheel.

  • initialPose – The starting pose estimate.

  1. __init__(self: wpimath._wpimath.MecanumDrivePoseEstimator3d, kinematics: wpimath._wpimath.MecanumDriveKinematics, gyroAngle: wpimath._wpimath.Rotation3d, wheelPositions: wpimath._wpimath.MecanumDriveWheelPositions, initialPose: wpimath._wpimath.Pose3d, stateStdDevs: Tuple[typing.SupportsFloat | typing.SupportsIndex, typing.SupportsFloat | typing.SupportsIndex, typing.SupportsFloat | typing.SupportsIndex, typing.SupportsFloat | typing.SupportsIndex], visionMeasurementStdDevs: Tuple[typing.SupportsFloat | typing.SupportsIndex, typing.SupportsFloat | typing.SupportsIndex, typing.SupportsFloat | typing.SupportsIndex, typing.SupportsFloat | typing.SupportsIndex]) -> None

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.

  • initialPose – The starting pose estimate.

  • stateStdDevs – Standard deviations of the pose estimate (x position in meters, y position in meters, z position in meters, and angle 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, z position in meters, and angle in radians). Increase these numbers to trust the vision pose measurement less.