MecanumDrivePoseEstimator

class wpimath.estimator.MecanumDrivePoseEstimator(*args, **kwargs)

Bases: pybind11_object

This class wraps an Unscented Kalman Filter 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 but more accurate drop-in for MecanumDriveOdometry.

update() should be called every robot loop. If your loops are faster or slower than the default of 0.02s, 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.

The state-space system used internally has the following states (x), inputs (u), and outputs (y):

\(x = [x, y, \theta]^T\) in the field-coordinate system containing x position, y position, and heading.

\(u = [v_x, v_y, \omega]^T\) containing x velocity, y velocity, and angular velocity in the field-coordinate system.

\(y = [x, y, \theta]^T\) from vision containing x position, y position, and heading; or \(y = [theta]^T\) containing gyro heading.

Overloaded function.

  1. __init__(self: wpimath._controls._controls.estimator.MecanumDrivePoseEstimator, kinematics: wpimath.kinematics._kinematics.MecanumDriveKinematics, gyroAngle: wpimath.geometry._geometry.Rotation2d, wheelPositions: wpimath.kinematics._kinematics.MecanumDriveWheelPositions, initialPose: wpimath.geometry._geometry.Pose2d) -> None

Constructs a MecanumDrivePoseEstimator 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, and 0.1 radians for heading. The default standard deviations of the vision measurements are 0.45 meters for x, 0.45 meters for y, and 0.45 radians for heading.

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._controls._controls.estimator.MecanumDrivePoseEstimator, kinematics: wpimath.kinematics._kinematics.MecanumDriveKinematics, gyroAngle: wpimath.geometry._geometry.Rotation2d, wheelPositions: wpimath.kinematics._kinematics.MecanumDriveWheelPositions, initialPose: wpimath.geometry._geometry.Pose2d, stateStdDevs: Tuple[float, float, float], visionMeasurementStdDevs: Tuple[float, float, float]) -> None

Constructs a MecanumDrivePoseEstimator.

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, 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.

addVisionMeasurement(*args, **kwargs)

Overloaded function.

  1. addVisionMeasurement(self: wpimath._controls._controls.estimator.MecanumDrivePoseEstimator, visionRobotPose: wpimath.geometry._geometry.Pose2d, timestamp: seconds) -> None

Add a vision measurement to the Kalman Filter. This will correct the odometry pose estimate while still accounting for measurement noise.

This method can be called as infrequently as you want, as long as you are calling Update() every loop.

To promote stability of the pose estimate and make it robust to bad vision data, we recommend only adding vision measurements that are already within one meter or so of the current pose estimate.

Parameters:
  • visionRobotPose – The pose of the robot as measured by the vision camera.

  • timestamp – The timestamp of the vision measurement in seconds. Note that if you don’t use your own time source by calling UpdateWithTime() then you must use a timestamp with an epoch since FPGA startup (i.e., the epoch of this timestamp is the same epoch as frc::Timer::GetFPGATimestamp().) This means that you should use frc::Timer::GetFPGATimestamp() as your time source or sync the epochs.

  1. addVisionMeasurement(self: wpimath._controls._controls.estimator.MecanumDrivePoseEstimator, visionRobotPose: wpimath.geometry._geometry.Pose2d, timestamp: seconds, visionMeasurementStdDevs: Tuple[float, float, float]) -> None

Adds a vision measurement to the Kalman Filter. This will correct the odometry pose estimate while still accounting for measurement noise.

This method can be called as infrequently as you want, as long as you are calling Update() every loop.

To promote stability of the pose estimate and make it robust to bad vision data, we recommend only adding vision measurements that are already within one meter or so of the current pose estimate.

Note that the vision measurement standard deviations passed into this method will continue to apply to future measurements until a subsequent call to SetVisionMeasurementStdDevs() or this method.

Parameters:
  • visionRobotPose – The pose of the robot as measured by the vision camera.

  • timestamp – The timestamp of the vision measurement in seconds. Note that if you don’t use your own time source by calling UpdateWithTime(), then you must use a timestamp with an epoch since FPGA startup (i.e., the epoch of this timestamp is the same epoch as frc::Timer::GetFPGATimestamp(). This means that you should use frc::Timer::GetFPGATimestamp() as your time source in this case.

  • 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.

getEstimatedPosition() wpimath.geometry._geometry.Pose2d

Gets the estimated robot pose.

Returns:

The estimated robot pose in meters.

resetPosition(gyroAngle: wpimath.geometry._geometry.Rotation2d, wheelPositions: wpimath.kinematics._kinematics.MecanumDriveWheelPositions, pose: wpimath.geometry._geometry.Pose2d) None

Resets the robot’s position on the field.

The gyroscope angle does not need to be reset in the user’s robot code. The library automatically takes care of offsetting the gyro angle.

Parameters:
  • gyroAngle – The angle reported by the gyroscope.

  • wheelPositions – The distances measured at each wheel.

  • pose – The position on the field that your robot is at.

setVisionMeasurementStdDevs(visionMeasurementStdDevs: Tuple[float, float, float]) None

Sets the pose estimator’s trust in vision measurements. This might be used to change trust in vision measurements after the autonomous period, or to change trust as distance to a vision target increases.

Parameters:

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.

update(gyroAngle: wpimath.geometry._geometry.Rotation2d, wheelPositions: wpimath.kinematics._kinematics.MecanumDriveWheelPositions) wpimath.geometry._geometry.Pose2d

Updates the pose estimator with wheel encoder and gyro information. This should be called every loop.

Parameters:
  • gyroAngle – The current gyro angle.

  • wheelPositions – The distances measured at each wheel.

Returns:

The estimated pose of the robot in meters.

updateWithTime(currentTime: seconds, gyroAngle: wpimath.geometry._geometry.Rotation2d, wheelPositions: wpimath.kinematics._kinematics.MecanumDriveWheelPositions) wpimath.geometry._geometry.Pose2d

Updates the pose estimator with wheel encoder and gyro information. This should be called every loop.

Parameters:
  • currentTime – Time at which this method was called, in seconds.

  • gyroAngle – The current gyroscope angle.

  • wheelPositions – The distances measured at each wheel.

Returns:

The estimated pose of the robot in meters.