1 package org
.usfirst
.frc
.team3501
.robot
.subsystems
;
3 import org
.usfirst
.frc
.team3501
.robot
.Constants
;
4 import org
.usfirst
.frc
.team3501
.robot
.commands
.driving
.JoystickDrive
;
5 import org
.usfirst
.frc
.team3501
.robot
.utils
.PIDController
;
7 import com
.ctre
.CANTalon
;
9 import edu
.wpi
.first
.wpilibj
.ADXRS450_Gyro
;
10 import edu
.wpi
.first
.wpilibj
.DoubleSolenoid
;
11 import edu
.wpi
.first
.wpilibj
.DoubleSolenoid
.Value
;
12 import edu
.wpi
.first
.wpilibj
.Encoder
;
13 import edu
.wpi
.first
.wpilibj
.RobotDrive
;
14 import edu
.wpi
.first
.wpilibj
.command
.Subsystem
;
16 public class DriveTrain
extends Subsystem
{
18 public static double driveP
, driveI
, driveD
;
19 public static double turnP
= 0.004, turnI
= 0.0013, turnD
= -0.005;
20 public static double driveStraightGyroP
= 0.01;
22 public static final double WHEEL_DIAMETER
= 6; // inches
23 public static final int ENCODER_PULSES_PER_REVOLUTION
= 256;
24 public static final double INCHES_PER_PULSE
= WHEEL_DIAMETER
* Math
.PI
25 / ENCODER_PULSES_PER_REVOLUTION
;
27 public static final double MAINTAIN_CLIMBED_POSITION
= 0;
28 public static final double TIME_TO_CLIMB_FOR
= 0;
29 public static final double CLIMBER_SPEED
= 0;
31 private static DriveTrain driveTrain
;
33 private final CANTalon frontLeft
, frontRight
, rearLeft
, rearRight
;
34 private final RobotDrive robotDrive
;
35 private final Encoder leftEncoder
, rightEncoder
;
36 private final DoubleSolenoid leftGearPiston
, rightGearPiston
;
38 private ADXRS450_Gyro imu
;
40 public boolean shouldBeClimbing
= false;
42 private PIDController driveController
;
43 private PIDController gyroController
;
45 private DriveTrain() {
47 driveController
= new PIDController(driveP
, driveI
, driveD
);
50 frontLeft
= new CANTalon(Constants
.DriveTrain
.FRONT_LEFT
);
51 frontRight
= new CANTalon(Constants
.DriveTrain
.FRONT_RIGHT
);
52 rearLeft
= new CANTalon(Constants
.DriveTrain
.REAR_LEFT
);
53 rearRight
= new CANTalon(Constants
.DriveTrain
.REAR_RIGHT
);
56 leftEncoder
= new Encoder(Constants
.DriveTrain
.ENCODER_LEFT_A
,
57 Constants
.DriveTrain
.ENCODER_LEFT_B
, false, Encoder
.EncodingType
.k4X
);
58 rightEncoder
= new Encoder(Constants
.DriveTrain
.ENCODER_RIGHT_A
,
59 Constants
.DriveTrain
.ENCODER_RIGHT_B
, false, Encoder
.EncodingType
.k4X
);
61 leftEncoder
.setDistancePerPulse(INCHES_PER_PULSE
);
62 rightEncoder
.setDistancePerPulse(INCHES_PER_PULSE
);
65 robotDrive
= new RobotDrive(frontLeft
, rearLeft
, frontRight
, rearRight
);
67 this.imu
= new ADXRS450_Gyro(Constants
.DriveTrain
.GYRO_PORT
);
69 // TODO: Not sure if MODULE_NUMBER should be the same for both
70 leftGearPiston
= new DoubleSolenoid(Constants
.DriveTrain
.PISTON_MODULE
,
71 Constants
.DriveTrain
.LEFT_GEAR_PISTON_FORWARD
,
72 Constants
.DriveTrain
.LEFT_GEAR_PISTON_REVERSE
);
73 rightGearPiston
= new DoubleSolenoid(Constants
.DriveTrain
.PISTON_MODULE
,
74 Constants
.DriveTrain
.RIGHT_GEAR_PISTON_FORWARD
,
75 Constants
.DriveTrain
.RIGHT_GEAR_PISTON_REVERSE
);
78 public PIDController
getDriveController() {
79 return this.driveController
;
82 public static DriveTrain
getDriveTrain() {
83 if (driveTrain
== null) {
84 driveTrain
= new DriveTrain();
90 public void setMotorValues(final double left
, final double right
) {
94 frontRight
.set(-right
);
95 rearRight
.set(-right
);
98 public void joystickDrive(final double thrust
, final double twist
) {
99 robotDrive
.arcadeDrive(thrust
, twist
, true);
103 setMotorValues(0, 0);
106 public double getLeftMotorVal() {
107 return (frontLeft
.get() + rearLeft
.get()) / 2;
110 public double getRightMotorVal() {
111 return (frontRight
.get() + rearRight
.get()) / 2;
116 public double getLeftEncoderDistance() {
117 return leftEncoder
.getDistance();
120 public double getRightEncoderDistance() {
121 return rightEncoder
.getDistance();
124 public void printEncoderOutput() {
125 System
.out
.println("left: " + getLeftEncoderDistance());
126 System
.out
.println("right: " + getRightEncoderDistance());
127 // System.out.println(getAvgEncoderDistance());
130 public double getAvgEncoderDistance() {
131 return (leftEncoder
.getDistance() + rightEncoder
.getDistance()) / 2;
134 public void resetEncoders() {
136 rightEncoder
.reset();
139 public double getLeftSpeed() {
140 return leftEncoder
.getRate();
143 public double getRightSpeed() {
144 return rightEncoder
.getRate();
147 public double getSpeed() {
148 return (getLeftSpeed() + getRightSpeed()) / 2.0;
151 // ------Gyro------//
152 public double getAngle() {
153 return this.imu
.getAngle();
156 public void resetGyro() {
161 * @return a value that is the current setpoint for the piston kReverse or
164 public Value
getLeftGearPistonValue() {
165 return leftGearPiston
.get();
169 * @return a value that is the current setpoint for the piston kReverse or
172 public Value
getRightGearPistonValue() {
173 return rightGearPiston
.get();
177 * Changes the ball shift gear assembly to high
179 public void setHighGear() {
180 changeGear(Constants
.DriveTrain
.HIGH_GEAR
);
184 * Changes the ball shift gear assembly to low
186 public void setLowGear() {
187 changeGear(Constants
.DriveTrain
.LOW_GEAR
);
191 * Changes the gear to a DoubleSolenoid.Value
193 private void changeGear(DoubleSolenoid
.Value gear
) {
194 leftGearPiston
.set(gear
);
195 rightGearPiston
.set(gear
);
199 protected void initDefaultCommand() {
200 setDefaultCommand(new JoystickDrive());