MecanumDriveOdometry

class wpimath.kinematics.MecanumDriveOdometry(kinematics: wpimath.kinematics._kinematics.MecanumDriveKinematics, gyroAngle: wpimath.geometry._geometry.Rotation2d, wheelPositions: wpimath.kinematics._kinematics.MecanumDriveWheelPositions, initialPose: wpimath.geometry._geometry.Pose2d = Pose2d(Translation2d(x=0.000000, y=0.000000), Rotation2d(0.000000)))

Bases: pybind11_object

Class for mecanum drive odometry. Odometry allows you to track the robot’s position on the field over a course of a match using readings from your mecanum wheel encoders.

Teams can use odometry during the autonomous period for complex tasks like path following. Furthermore, odometry can be used for latency compensation when using computer-vision systems.

Constructs a MecanumDriveOdometry object.

Parameters:
  • kinematics – The mecanum drive kinematics for your drivetrain.

  • gyroAngle – The angle reported by the gyroscope.

  • wheelPositions – The current distances measured by each wheel.

  • initialPose – The starting position of the robot on the field.

getPose() wpimath.geometry._geometry.Pose2d

Returns the position of the robot on the field.

Returns:

The pose of the robot.

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 here on 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 current distances measured by each wheel.

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

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

Updates the robot’s position on the field using forward kinematics and integration of the pose over time. This method takes in an angle parameter which is used instead of the angular rate that is calculated from forward kinematics, in addition to the current distance measurement at each wheel.

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

  • wheelPositions – The current distances measured by each wheel.

Returns:

The new pose of the robot.