2026-02-20 18:30:35 -05:00
|
|
|
#
|
|
|
|
|
# Copyright (c) FIRST and other WPILib contributors.
|
|
|
|
|
# Open Source Software; you can modify and/or share it under the terms of
|
|
|
|
|
# the WPILib BSD license file in the root directory of this project.
|
|
|
|
|
#
|
|
|
|
|
import math
|
|
|
|
|
|
|
|
|
|
import wpilib
|
|
|
|
|
import wpimath
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
class Drivetrain:
|
|
|
|
|
"""Represents a mecanum drive style drivetrain."""
|
|
|
|
|
|
2026-03-06 14:19:15 -08:00
|
|
|
kMaxVelocity = 3.0 # 3 meters per second
|
|
|
|
|
kMaxAngularVelocity = math.pi # 1/2 rotation per second
|
2026-02-20 18:30:35 -05:00
|
|
|
|
|
|
|
|
def __init__(self) -> None:
|
|
|
|
|
self.frontLeftMotor = wpilib.PWMSparkMax(1)
|
|
|
|
|
self.frontRightMotor = wpilib.PWMSparkMax(2)
|
|
|
|
|
self.backLeftMotor = wpilib.PWMSparkMax(3)
|
|
|
|
|
self.backRightMotor = wpilib.PWMSparkMax(4)
|
|
|
|
|
|
|
|
|
|
self.frontLeftEncoder = wpilib.Encoder(0, 1)
|
|
|
|
|
self.frontRightEncoder = wpilib.Encoder(2, 3)
|
|
|
|
|
self.backLeftEncoder = wpilib.Encoder(4, 5)
|
|
|
|
|
self.backRightEncoder = wpilib.Encoder(6, 7)
|
|
|
|
|
|
|
|
|
|
self.frontLeftLocation = wpimath.Translation2d(0.381, 0.381)
|
|
|
|
|
self.frontRightLocation = wpimath.Translation2d(0.381, -0.381)
|
|
|
|
|
self.backLeftLocation = wpimath.Translation2d(-0.381, 0.381)
|
|
|
|
|
self.backRightLocation = wpimath.Translation2d(-0.381, -0.381)
|
|
|
|
|
|
|
|
|
|
self.frontLeftPIDController = wpimath.PIDController(1, 0, 0)
|
|
|
|
|
self.frontRightPIDController = wpimath.PIDController(1, 0, 0)
|
|
|
|
|
self.backLeftPIDController = wpimath.PIDController(1, 0, 0)
|
|
|
|
|
self.backRightPIDController = wpimath.PIDController(1, 0, 0)
|
|
|
|
|
|
|
|
|
|
self.imu = wpilib.OnboardIMU(wpilib.OnboardIMU.MountOrientation.kFlat)
|
|
|
|
|
|
|
|
|
|
self.kinematics = wpimath.MecanumDriveKinematics(
|
|
|
|
|
self.frontLeftLocation,
|
|
|
|
|
self.frontRightLocation,
|
|
|
|
|
self.backLeftLocation,
|
|
|
|
|
self.backRightLocation,
|
|
|
|
|
)
|
|
|
|
|
|
|
|
|
|
self.odometry = wpimath.MecanumDriveOdometry(
|
|
|
|
|
self.kinematics, self.imu.getRotation2d(), self.getCurrentDistances()
|
|
|
|
|
)
|
|
|
|
|
|
|
|
|
|
# Gains are for example purposes only - must be determined for your own robot!
|
|
|
|
|
self.feedforward = wpimath.SimpleMotorFeedforwardMeters(1, 3)
|
|
|
|
|
|
|
|
|
|
self.imu.resetYaw()
|
|
|
|
|
|
|
|
|
|
# We need to invert one side of the drivetrain so that positive voltages
|
|
|
|
|
# result in both sides moving forward. Depending on how your robot's
|
|
|
|
|
# gearbox is constructed, you might have to invert the left side instead.
|
|
|
|
|
self.frontRightMotor.setInverted(True)
|
|
|
|
|
self.backRightMotor.setInverted(True)
|
|
|
|
|
|
2026-03-06 14:19:15 -08:00
|
|
|
def getCurrentState(self) -> wpimath.MecanumDriveWheelVelocities:
|
2026-02-20 18:30:35 -05:00
|
|
|
"""Returns the current state of the drivetrain."""
|
2026-03-06 14:19:15 -08:00
|
|
|
return wpimath.MecanumDriveWheelVelocities(
|
2026-02-20 18:30:35 -05:00
|
|
|
self.frontLeftEncoder.getRate(),
|
|
|
|
|
self.frontRightEncoder.getRate(),
|
|
|
|
|
self.backLeftEncoder.getRate(),
|
|
|
|
|
self.backRightEncoder.getRate(),
|
|
|
|
|
)
|
|
|
|
|
|
|
|
|
|
def getCurrentDistances(self) -> wpimath.MecanumDriveWheelPositions:
|
|
|
|
|
"""Returns the current distances measured by the drivetrain."""
|
|
|
|
|
positions = wpimath.MecanumDriveWheelPositions()
|
|
|
|
|
positions.frontLeft = self.frontLeftEncoder.getDistance()
|
|
|
|
|
positions.frontRight = self.frontRightEncoder.getDistance()
|
|
|
|
|
positions.rearLeft = self.backLeftEncoder.getDistance()
|
|
|
|
|
positions.rearRight = self.backRightEncoder.getDistance()
|
|
|
|
|
return positions
|
|
|
|
|
|
2026-03-06 14:19:15 -08:00
|
|
|
def setVelocities(self, velocities: wpimath.MecanumDriveWheelVelocities) -> None:
|
|
|
|
|
"""Sets the desired velocities for each wheel."""
|
|
|
|
|
frontLeftFeedforward = self.feedforward.calculate(velocities.frontLeft)
|
|
|
|
|
frontRightFeedforward = self.feedforward.calculate(velocities.frontRight)
|
|
|
|
|
backLeftFeedforward = self.feedforward.calculate(velocities.rearLeft)
|
|
|
|
|
backRightFeedforward = self.feedforward.calculate(velocities.rearRight)
|
2026-02-20 18:30:35 -05:00
|
|
|
|
|
|
|
|
frontLeftOutput = self.frontLeftPIDController.calculate(
|
2026-03-06 14:19:15 -08:00
|
|
|
self.frontLeftEncoder.getRate(), velocities.frontLeft
|
2026-02-20 18:30:35 -05:00
|
|
|
)
|
|
|
|
|
frontRightOutput = self.frontRightPIDController.calculate(
|
2026-03-06 14:19:15 -08:00
|
|
|
self.frontRightEncoder.getRate(), velocities.frontRight
|
2026-02-20 18:30:35 -05:00
|
|
|
)
|
|
|
|
|
backLeftOutput = self.frontLeftPIDController.calculate(
|
2026-03-06 14:19:15 -08:00
|
|
|
self.backLeftEncoder.getRate(), velocities.rearLeft
|
2026-02-20 18:30:35 -05:00
|
|
|
)
|
|
|
|
|
backRightOutput = self.frontRightPIDController.calculate(
|
2026-03-06 14:19:15 -08:00
|
|
|
self.backRightEncoder.getRate(), velocities.rearRight
|
2026-02-20 18:30:35 -05:00
|
|
|
)
|
|
|
|
|
|
|
|
|
|
self.frontLeftMotor.setVoltage(frontLeftOutput + frontLeftFeedforward)
|
|
|
|
|
self.frontRightMotor.setVoltage(frontRightOutput + frontRightFeedforward)
|
|
|
|
|
self.backLeftMotor.setVoltage(backLeftOutput + backLeftFeedforward)
|
|
|
|
|
self.backRightMotor.setVoltage(backRightOutput + backRightFeedforward)
|
|
|
|
|
|
|
|
|
|
def drive(
|
|
|
|
|
self,
|
2026-03-06 14:19:15 -08:00
|
|
|
xVelocity: float,
|
|
|
|
|
yVelocity: float,
|
2026-02-20 18:30:35 -05:00
|
|
|
rot: float,
|
|
|
|
|
fieldRelative: bool,
|
|
|
|
|
periodSeconds: float,
|
|
|
|
|
) -> None:
|
|
|
|
|
"""Method to drive the robot using joystick info."""
|
2026-03-06 14:19:15 -08:00
|
|
|
chassisVelocities = wpimath.ChassisVelocities(xVelocity, yVelocity, rot)
|
2026-02-20 18:30:35 -05:00
|
|
|
if fieldRelative:
|
2026-03-09 00:38:21 -04:00
|
|
|
chassisVelocities = chassisVelocities.toRobotRelative(
|
|
|
|
|
self.imu.getRotation2d()
|
|
|
|
|
)
|
2026-02-20 18:30:35 -05:00
|
|
|
|
2026-03-06 14:19:15 -08:00
|
|
|
self.setVelocities(
|
|
|
|
|
self.kinematics.toWheelVelocities(
|
|
|
|
|
chassisVelocities.discretize(periodSeconds)
|
|
|
|
|
).desaturate(self.kMaxVelocity)
|
2026-02-20 18:30:35 -05:00
|
|
|
)
|
|
|
|
|
|
|
|
|
|
def updateOdometry(self) -> None:
|
|
|
|
|
"""Updates the field-relative position."""
|
|
|
|
|
self.odometry.update(self.imu.getRotation2d(), self.getCurrentDistances())
|