|
| 1 | +package com.spikes2212.command.drivetrains; |
| 2 | + |
| 3 | +import com.spikes2212.command.DashboardedSubsystem; |
| 4 | +import com.spikes2212.util.MotorControllerGroup; |
| 5 | +import edu.wpi.first.networktables.NetworkTable; |
| 6 | +import edu.wpi.first.wpilibj.RobotController; |
| 7 | +import edu.wpi.first.wpilibj.drive.DifferentialDrive; |
| 8 | +import edu.wpi.first.wpilibj.motorcontrol.MotorController; |
| 9 | + |
| 10 | +/** |
| 11 | + * This class represents a type of drivetrain that its left and right sides are controlled independently, |
| 12 | + * allowing it to move by giving each side a speed value separately. |
| 13 | + * |
| 14 | + * <p> It can move forwards/backwards by giving both its sides an equal speed or |
| 15 | + * turn by giving the sides different speeds. </p> |
| 16 | + * |
| 17 | + * @author Yuval Levy |
| 18 | + * @see DashboardedSubsystem |
| 19 | + */ |
| 20 | +public class TankDrivetrain extends DashboardedSubsystem { |
| 21 | + |
| 22 | + private static final String DEFAULT_NAMESPACE_NAME = "tank drivetrain"; |
| 23 | + |
| 24 | + protected final MotorController leftController; |
| 25 | + protected final MotorController rightController; |
| 26 | + |
| 27 | + private final DifferentialDrive drive; |
| 28 | + |
| 29 | + public TankDrivetrain(String namespaceName, MotorController leftController, MotorController rightController) { |
| 30 | + super(namespaceName); |
| 31 | + this.leftController = leftController; |
| 32 | + this.rightController = rightController; |
| 33 | + rightController.setInverted(true); |
| 34 | + drive = new DifferentialDrive(leftController, rightController); |
| 35 | + drive.setSafetyEnabled(false); |
| 36 | + } |
| 37 | + |
| 38 | + public TankDrivetrain(MotorController leftController, MotorController rightController) { |
| 39 | + this(getClassName(DEFAULT_NAMESPACE_NAME), leftController, rightController); |
| 40 | + } |
| 41 | + |
| 42 | + public TankDrivetrain(String namespaceName, MotorController leftMaster, MotorController leftSlave, |
| 43 | + MotorController rightMaster, MotorController rightSlave) { |
| 44 | + this(namespaceName, new MotorControllerGroup(leftMaster, leftSlave), |
| 45 | + new MotorControllerGroup(rightMaster, rightSlave)); |
| 46 | + } |
| 47 | + |
| 48 | + public TankDrivetrain(MotorController leftMaster, MotorController leftSlave, |
| 49 | + MotorController rightMaster, MotorController rightSlave) { |
| 50 | + this(new MotorControllerGroup(leftMaster, leftSlave), |
| 51 | + new MotorControllerGroup(rightMaster, rightSlave)); |
| 52 | + } |
| 53 | + |
| 54 | + /** |
| 55 | + * Moves both sides of this drivetrain by the given speeds for each side. |
| 56 | + * |
| 57 | + * @param leftSpeed the speed to set to the left side (-1 to 1). Positive values move this side forward |
| 58 | + * @param rightSpeed the speed to set to the right side (-1 to 1). Positive values move this side forward |
| 59 | + */ |
| 60 | + public void tankDrive(double leftSpeed, double rightSpeed) { |
| 61 | + drive.tankDrive(leftSpeed, rightSpeed, false); |
| 62 | + } |
| 63 | + |
| 64 | + /** |
| 65 | + * Moves both sides of this drivetrain by the given speeds for each side. |
| 66 | + * |
| 67 | + * @param leftSpeed the speed to set to the left side (-1 to 1). Positive values move this side forward |
| 68 | + * @param rightSpeed the speed to set to the right side (-1 to 1). Positive values move this side forward |
| 69 | + * @param squareInputs whether to square the given inputs before putting them in the speed controllers |
| 70 | + */ |
| 71 | + public void tankDrive(double leftSpeed, double rightSpeed, boolean squareInputs) { |
| 72 | + drive.tankDrive(leftSpeed, rightSpeed, squareInputs); |
| 73 | + } |
| 74 | + |
| 75 | + /** |
| 76 | + * Moves both sides of this drivetrain by the given voltages for each side. |
| 77 | + * |
| 78 | + * @param leftVoltage the voltage to set to the left side (-12 to 12). Positive values move this side forward |
| 79 | + * @param rightVoltage the voltage to set to the right side (-12 to 12). Positive values move this side forward |
| 80 | + */ |
| 81 | + public void tankDriveVoltages(double leftVoltage, double rightVoltage) { |
| 82 | + tankDrive(leftVoltage / RobotController.getBatteryVoltage(), |
| 83 | + rightVoltage / RobotController.getBatteryVoltage(), false); |
| 84 | + } |
| 85 | + |
| 86 | + /** |
| 87 | + * Moves the drivetrain by the given forward and angular speed. |
| 88 | + * |
| 89 | + * @param moveValue the forward movement speed (-1 to 1) |
| 90 | + * @param rotateValue the angular movement speed (-1 to 1). Positive values go clockwise |
| 91 | + */ |
| 92 | + public void arcadeDrive(double moveValue, double rotateValue) { |
| 93 | + drive.arcadeDrive(moveValue, rotateValue, false); |
| 94 | + } |
| 95 | + |
| 96 | + /** |
| 97 | + * Moves the drivetrain by the given forward and angular speed. |
| 98 | + * |
| 99 | + * @param moveValue the forward movement speed (-1 to 1) |
| 100 | + * @param rotateValue the angular movement speed (-1 to 1). Positive values go clockwise |
| 101 | + * @param squareInputs whether to square the given inputs before putting them in the speed controllers |
| 102 | + */ |
| 103 | + public void arcadeDrive(double moveValue, double rotateValue, boolean squareInputs) { |
| 104 | + drive.arcadeDrive(moveValue, rotateValue, squareInputs); |
| 105 | + } |
| 106 | + |
| 107 | + /** |
| 108 | + * Moves the drivetrain by the given forward and angular voltage. |
| 109 | + * |
| 110 | + * @param moveVoltage the forward movement voltage (-12 to 12) |
| 111 | + * @param rotateVoltage the angular movement voltage (-12 to 12). Positive values go clockwise |
| 112 | + */ |
| 113 | + public void arcadeDriveVoltages(double moveVoltage, double rotateVoltage) { |
| 114 | + arcadeDrive(moveVoltage / RobotController.getBatteryVoltage(), |
| 115 | + rotateVoltage / RobotController.getBatteryVoltage(), false); |
| 116 | + } |
| 117 | + |
| 118 | + /** |
| 119 | + * Moves the drivetrain while rotating it at a given curvature. |
| 120 | + * |
| 121 | + * @param speed the forward movement speed (-1 to 1) |
| 122 | + * @param curvature the curvature of the robot's path (-1 to 1). Positive values go clockwise |
| 123 | + */ |
| 124 | + public void curvatureDrive(double speed, double curvature) { |
| 125 | + drive.curvatureDrive(speed, curvature, true); |
| 126 | + } |
| 127 | + |
| 128 | + /** |
| 129 | + * Moves the left side of this drivetrain by a given speed. |
| 130 | + * |
| 131 | + * @param leftSpeed the speed to set to the left side (-1 to 1). Positive values move this side forward |
| 132 | + */ |
| 133 | + public void setLeft(double leftSpeed) { |
| 134 | + leftController.set(leftSpeed); |
| 135 | + } |
| 136 | + |
| 137 | + /** |
| 138 | + * Moves the right side of this drivetrain by a given speed. |
| 139 | + * |
| 140 | + * @param rightSpeed the speed to set to the right side (-1 to 1). Positive values move this side forward |
| 141 | + */ |
| 142 | + public void setRight(double rightSpeed) { |
| 143 | + rightController.set(rightSpeed); |
| 144 | + } |
| 145 | + |
| 146 | + /** |
| 147 | + * Moves the left side of this drivetrain by a given voltage. |
| 148 | + * |
| 149 | + * @param leftVoltage the voltage to set to the left side (-12 to 12). Positive values move this side forward |
| 150 | + */ |
| 151 | + public void setLeftVoltage(double leftVoltage) { |
| 152 | + setLeft(leftVoltage / RobotController.getBatteryVoltage()); |
| 153 | + } |
| 154 | + |
| 155 | + /** |
| 156 | + * Moves the right side of this drivetrain by a given voltage. |
| 157 | + * |
| 158 | + * @param rightVoltage the voltage to set to the right side (-12 to 12). Positive values move this side forward |
| 159 | + */ |
| 160 | + public void setRightVoltage(double rightVoltage) { |
| 161 | + setRight(rightVoltage / RobotController.getBatteryVoltage()); |
| 162 | + } |
| 163 | + |
| 164 | + /** |
| 165 | + * Stops the drivetrain. |
| 166 | + */ |
| 167 | + public void stop() { |
| 168 | + leftController.stopMotor(); |
| 169 | + rightController.stopMotor(); |
| 170 | + } |
| 171 | + |
| 172 | + /** |
| 173 | + * Sets the motor safety feature of the speed controllers on/off. |
| 174 | + * |
| 175 | + * @param enabled whether motor safety should be enabled |
| 176 | + */ |
| 177 | + public void setMotorSafety(boolean enabled) { |
| 178 | + drive.setSafetyEnabled(enabled); |
| 179 | + } |
| 180 | + |
| 181 | + /** |
| 182 | + * Adds any commands or data from this subsystem to the {@link NetworkTable}s. |
| 183 | + */ |
| 184 | + @Override |
| 185 | + public void configureDashboard() { |
| 186 | + } |
| 187 | +} |
0 commit comments