Class MecanumDriveOdometry

java.lang.Object
edu.wpi.first.math.kinematics.Odometry<MecanumDriveWheelPositions>
edu.wpi.first.math.kinematics.MecanumDriveOdometry

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.

  • Constructor Details

    • MecanumDriveOdometry

      public MecanumDriveOdometry(MecanumDriveKinematics kinematics, Rotation2d gyroAngle, MecanumDriveWheelPositions wheelPositions, Pose2d initialPoseMeters)
      Constructs a MecanumDriveOdometry object.
      Parameters:
      kinematics - The mecanum drive kinematics for your drivetrain.
      gyroAngle - The angle reported by the gyroscope.
      wheelPositions - The distances driven by each wheel.
      initialPoseMeters - The starting position of the robot on the field.
    • MecanumDriveOdometry

      public MecanumDriveOdometry(MecanumDriveKinematics kinematics, Rotation2d gyroAngle, MecanumDriveWheelPositions wheelPositions)
      Constructs a MecanumDriveOdometry object with the default pose at the origin.
      Parameters:
      kinematics - The mecanum drive kinematics for your drivetrain.
      gyroAngle - The angle reported by the gyroscope.
      wheelPositions - The distances driven by each wheel.