|
| 1 | +# |
| 2 | +# Copyright (c) FIRST and other WPILib contributors. |
| 3 | +# Open Source Software; you can modify and/or share it under the terms of |
| 4 | +# the WPILib BSD license file in the root directory of this project. |
| 5 | +# |
| 6 | + |
| 7 | +import wpilib.drive |
| 8 | +import wpimath.controller |
| 9 | +import wpimath.geometry |
| 10 | +from wpimath.kinematics import ChassisSpeeds |
| 11 | +import wpimath.units |
| 12 | + |
| 13 | +import math |
| 14 | + |
| 15 | + |
| 16 | +class Drivetrain: |
| 17 | + """Represents a differential drive style drivetrain.""" |
| 18 | + |
| 19 | + kMaxSpeed = 3.0 # 3 meters per second |
| 20 | + kMaxAngularSpeed = math.pi # 1/2 rotation per second |
| 21 | + |
| 22 | + def __init__(self): |
| 23 | + self.frontLeftMotor = wpilib.PWMSparkMax(1) |
| 24 | + self.frontRightMotor = wpilib.PWMSparkMax(2) |
| 25 | + self.backLeftMotor = wpilib.PWMSparkMax(3) |
| 26 | + self.backRightMotor = wpilib.PWMSparkMax(4) |
| 27 | + |
| 28 | + self.frontLeftEncoder = wpilib.Encoder(0, 1) |
| 29 | + self.frontRightEncoder = wpilib.Encoder(2, 3) |
| 30 | + self.backLeftEncoder = wpilib.Encoder(4, 5) |
| 31 | + self.backRightEncoder = wpilib.Encoder(6, 7) |
| 32 | + |
| 33 | + frontLeftLocation = wpimath.geometry.Translation2d(0.381, 0.381) |
| 34 | + frontRightLocation = wpimath.geometry.Translation2d(0.381, -0.381) |
| 35 | + backLeftLocation = wpimath.geometry.Translation2d(-0.381, 0.381) |
| 36 | + backRightLocation = wpimath.geometry.Translation2d(-0.381, -0.381) |
| 37 | + |
| 38 | + self.frontLeftPIDController = wpimath.controller.PIDController(1, 0, 0) |
| 39 | + self.frontRightPIDController = wpimath.controller.PIDController(1, 0, 0) |
| 40 | + self.backLeftPIDController = wpimath.controller.PIDController(1, 0, 0) |
| 41 | + self.backRightPIDController = wpimath.controller.PIDController(1, 0, 0) |
| 42 | + |
| 43 | + self.gyro = wpilib.AnalogGyro(0) |
| 44 | + |
| 45 | + self.kinematics = wpimath.kinematics.MecanumDriveKinematics( |
| 46 | + frontLeftLocation, frontRightLocation, backLeftLocation, backRightLocation |
| 47 | + ) |
| 48 | + |
| 49 | + self.odometry = wpimath.kinematics.MecanumDriveOdometry( |
| 50 | + self.kinematics, self.gyro.getRotation2d(), self.getCurrentDistances() |
| 51 | + ) |
| 52 | + |
| 53 | + # Gains are for example purposes only - must be determined for your own robot! |
| 54 | + self.feedforward = wpimath.controller.SimpleMotorFeedforwardMeters(1, 3) |
| 55 | + |
| 56 | + self.gyro.reset() |
| 57 | + |
| 58 | + # We need to invert one side of the drivetrain so that positive voltages |
| 59 | + # result in both sides moving forward. Depending on how your robot's |
| 60 | + # gearbox is constructed, you might have to invert the left side instead. |
| 61 | + self.frontRightMotor.setInverted(True) |
| 62 | + self.backRightMotor.setInverted(True) |
| 63 | + |
| 64 | + def getCurrentState(self) -> wpimath.kinematics.MecanumDriveWheelSpeeds: |
| 65 | + """Returns the current state of the drivetrain.""" |
| 66 | + return wpimath.kinematics.MecanumDriveWheelSpeeds( |
| 67 | + self.frontLeftEncoder.getRate(), |
| 68 | + self.frontRightEncoder.getRate(), |
| 69 | + self.backLeftEncoder.getRate(), |
| 70 | + self.backRightEncoder.getRate(), |
| 71 | + ) |
| 72 | + |
| 73 | + def getCurrentDistances(self) -> wpimath.kinematics.MecanumDriveWheelPositions: |
| 74 | + """Returns the current distances measured by the drivetrain.""" |
| 75 | + pos = wpimath.kinematics.MecanumDriveWheelPositions() |
| 76 | + |
| 77 | + pos.frontLeft = self.frontLeftEncoder.getDistance() |
| 78 | + pos.frontRight = self.frontRightEncoder.getDistance() |
| 79 | + pos.rearLeft = self.backLeftEncoder.getDistance() |
| 80 | + pos.rearRight = self.backRightEncoder.getDistance() |
| 81 | + |
| 82 | + return pos |
| 83 | + |
| 84 | + def setSpeeds(self, speeds: wpimath.kinematics.MecanumDriveWheelSpeeds): |
| 85 | + """Sets the desired speeds for each wheel.""" |
| 86 | + frontLeftFeedforward = self.feedforward.calculate(speeds.frontLeft) |
| 87 | + frontRightFeedforward = self.feedforward.calculate(speeds.frontRight) |
| 88 | + backLeftFeedforward = self.feedforward.calculate(speeds.rearLeft) |
| 89 | + backRightFeedforward = self.feedforward.calculate(speeds.rearRight) |
| 90 | + |
| 91 | + frontLeftOutput = self.frontLeftPIDController.calculate( |
| 92 | + self.frontLeftEncoder.getRate(), speeds.frontLeft |
| 93 | + ) |
| 94 | + frontRightOutput = self.frontRightPIDController.calculate( |
| 95 | + self.frontRightEncoder.getRate(), speeds.frontRight |
| 96 | + ) |
| 97 | + backLeftOutput = self.frontLeftPIDController.calculate( |
| 98 | + self.backLeftEncoder.getRate(), speeds.rearLeft |
| 99 | + ) |
| 100 | + backRightOutput = self.frontRightPIDController.calculate( |
| 101 | + self.backRightEncoder.getRate(), speeds.rearRight |
| 102 | + ) |
| 103 | + |
| 104 | + self.frontLeftMotor.setVoltage(frontLeftOutput + frontLeftFeedforward) |
| 105 | + self.frontRightMotor.setVoltage(frontRightOutput + frontRightFeedforward) |
| 106 | + self.backLeftMotor.setVoltage(backLeftOutput + backLeftFeedforward) |
| 107 | + self.backRightMotor.setVoltage(backRightOutput + backRightFeedforward) |
| 108 | + |
| 109 | + def drive( |
| 110 | + self, |
| 111 | + xSpeed: float, |
| 112 | + ySpeed: float, |
| 113 | + rot: float, |
| 114 | + fieldRelative: bool, |
| 115 | + periodSeconds: float, |
| 116 | + ): |
| 117 | + """Method to drive the robot using joystick info.""" |
| 118 | + mecanumDriveWheelSpeeds = self.kinematics.toWheelSpeeds( |
| 119 | + ChassisSpeeds.discretize( |
| 120 | + ChassisSpeeds.fromFieldRelativeSpeeds( |
| 121 | + xSpeed, ySpeed, rot, self.gyro.getRotation2d() |
| 122 | + ) |
| 123 | + if fieldRelative |
| 124 | + else ChassisSpeeds(xSpeed, ySpeed, rot), |
| 125 | + periodSeconds, |
| 126 | + ) |
| 127 | + ) |
| 128 | + mecanumDriveWheelSpeeds.desaturate(self.kMaxSpeed) |
| 129 | + self.setSpeeds(mecanumDriveWheelSpeeds) |
| 130 | + |
| 131 | + def updateOdometry(self): |
| 132 | + """Updates the field-relative position.""" |
| 133 | + self.odometry.update(self.gyro.getRotation2d(), self.getCurrentDistances()) |
0 commit comments