1 package org
.usfirst
.frc
.team3501
.robot
.subsystems
;
3 import org
.usfirst
.frc
.team3501
.robot
.Constants
;
4 import org
.usfirst
.frc
.team3501
.robot
.GyroLib
;
5 import org
.usfirst
.frc
.team3501
.robot
.MathLib
;
6 import org
.usfirst
.frc
.team3501
.robot
.commands
.driving
.JoystickDrive
;
8 import edu
.wpi
.first
.wpilibj
.CANTalon
;
9 import edu
.wpi
.first
.wpilibj
.CounterBase
.EncodingType
;
10 import edu
.wpi
.first
.wpilibj
.Encoder
;
11 import edu
.wpi
.first
.wpilibj
.I2C
;
12 import edu
.wpi
.first
.wpilibj
.RobotDrive
;
13 import edu
.wpi
.first
.wpilibj
.command
.PIDSubsystem
;
15 public class DriveTrain
extends PIDSubsystem
{
16 private static double pidOutput
= 0;
17 private static double encoderTolerance
= 8.0, gyroTolerance
= 5.0;
18 private int DRIVE_MODE
= 1;
20 private static final int MANUAL_MODE
= 1, ENCODER_MODE
= 2, GYRO_MODE
= 3;
22 private Encoder leftEncoder
, rightEncoder
;
23 private CANTalon frontLeft
, frontRight
, rearLeft
, rearRight
;
24 private RobotDrive robotDrive
;
31 frontLeft
= new CANTalon(Constants
.DriveTrain
.FRONT_LEFT
);
32 frontRight
= new CANTalon(Constants
.DriveTrain
.FRONT_RIGHT
);
33 rearLeft
= new CANTalon(Constants
.DriveTrain
.REAR_LEFT
);
34 rearRight
= new CANTalon(Constants
.DriveTrain
.REAR_RIGHT
);
36 robotDrive
= new RobotDrive(frontLeft
, rearLeft
, frontRight
, rearRight
);
37 leftEncoder
= new Encoder(Constants
.DriveTrain
.ENCODER_LEFT_A
,
38 Constants
.DriveTrain
.ENCODER_LEFT_B
, false, EncodingType
.k4X
);
39 rightEncoder
= new Encoder(Constants
.DriveTrain
.ENCODER_RIGHT_A
,
40 Constants
.DriveTrain
.ENCODER_RIGHT_B
, false, EncodingType
.k4X
);
41 leftEncoder
.setDistancePerPulse(Constants
.DriveTrain
.INCHES_PER_PULSE
);
42 rightEncoder
.setDistancePerPulse(Constants
.DriveTrain
.INCHES_PER_PULSE
);
44 leftEncoder
.setDistancePerPulse(Constants
.DriveTrain
.INCHES_PER_PULSE
);
45 rightEncoder
.setDistancePerPulse(Constants
.DriveTrain
.INCHES_PER_PULSE
);
47 gyro
= new GyroLib(I2C
.Port
.kOnboard
, false);
49 DRIVE_MODE
= Constants
.DriveTrain
.ENCODER_MODE
;
57 protected void initDefaultCommand() {
58 setDefaultCommand(new JoystickDrive());
61 public void printOutput() {
62 System
.out
.println("PIDOutput: " + pidOutput
);
65 private double getAvgEncoderDistance() {
66 return (leftEncoder
.getDistance() + rightEncoder
.getDistance()) / 2;
69 public boolean reachedTarget() {
70 if (this.onTarget()) {
82 public void resetEncoders() {
87 public double getRightSpeed() {
88 return rightEncoder
.getRate(); // in inches per second
91 public double getLeftSpeed() {
92 return leftEncoder
.getRate(); // in inches per second
95 public double getSpeed() {
96 return (getLeftSpeed() + getRightSpeed()) / 2.0; // in inches per second
99 public double getRightDistance() {
100 return rightEncoder
.getDistance(); // in inches
103 public double getLeftDistance() {
104 return leftEncoder
.getDistance(); // in inches
107 public double getError() {
108 if (DRIVE_MODE
== Constants
.DriveTrain
.ENCODER_MODE
)
109 return Math
.abs(this.getSetpoint() - getAvgEncoderDistance());
111 return Math
.abs(this.getSetpoint() + getGyroAngle());
114 public double getGyroAngle() {
115 return gyro
.getRotationZ().getAngle();
118 public void resetGyro() {
122 public void printEncoder(int i
, int n
) {
124 System
.out
.println("Left: " + this.getLeftDistance());
125 System
.out
.println("Right: " + this.getRightDistance());
130 public void printGyroOutput() {
131 System
.out
.println("Gyro Angle" + -this.getGyroAngle());
134 public double getOutput() {
138 public void updatePID() {
139 if (DRIVE_MODE
== Constants
.DriveTrain
.ENCODER_MODE
)
140 this.getPIDController().setPID(kp
, ki
, kd
);
142 this.getPIDController().setPID(gp
, gd
, gi
);
145 public CANTalon
getFrontLeft() {
149 public CANTalon
getFrontRight() {
153 public CANTalon
getRearLeft() {
157 public CANTalon
getRearRight() {
161 public int getMode() {
166 protected void usePIDOutput(double output
) {
169 if (DRIVE_MODE
== Constants
.DriveTrain
.ENCODER_MODE
) {
170 double drift
= this.getLeftDistance() - this.getRightDistance();
171 if (Math
.abs(output
) > 0 && Math
.abs(output
) < 0.3)
172 output
= Math
.signum(output
) * 0.3;
174 right
= output
+ drift
* kp
/ 10;
176 else if (DRIVE_MODE
== Constants
.DriveTrain
.GYRO_MODE
) {
185 protected double returnPIDInput() {
186 return sensorFeedback();
189 private double sensorFeedback() {
190 if (DRIVE_MODE
== Constants
.DriveTrain
.ENCODER_MODE
)
191 return getAvgEncoderDistance();
192 else if (DRIVE_MODE
== Constants
.DriveTrain
.GYRO_MODE
)
193 return -this.getGyroAngle();
194 // counterclockwise is positive on joystick but we want it to be negative
199 public void drive(double left
, double right
) {
200 robotDrive
.tankDrive(-left
, -right
);
201 // dunno why but inverted drive (- values is forward)
204 public void driveDistance(double dist
, double maxTimeOut
) {
205 dist
= MathLib
.constrain(dist
, -100, 100);
210 public void setEncoderPID() {
211 DRIVE_MODE
= Constants
.DriveTrain
.ENCODER_MODE
;
213 this.setAbsoluteTolerance(encoderTolerance
);
214 this.setOutputRange(-1.0, 1.0);
215 this.setInputRange(-200.0, 200.0);
219 private void setGyroPID() {
220 DRIVE_MODE
= Constants
.DriveTrain
.GYRO_MODE
;
222 this.getPIDController().setPID(gp
, gi
, gd
);
224 this.setAbsoluteTolerance(gyroTolerance
);
225 this.setOutputRange(-1.0, 1.0);
226 this.setInputRange(-360.0, 360.0);
230 public void turnAngle(double angle
) {
231 angle
= MathLib
.constrain(angle
, -360, 360);
236 public void setMotorSpeeds(double left
, double right
) {
237 // positive setpoint to left side makes it go backwards
238 // positive setpoint to right side makes it go forwards.
239 frontLeft
.set(-left
);
241 frontRight
.set(right
);
242 rearRight
.set(right
);
245 private static double kp
= 0.013, ki
= 0.000015, kd
= -0.002;
246 private static double gp
= 0.018, gi
= 0.000015, gd
= 0;