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
.DoubleSolenoid
;
11 import edu
.wpi
.first
.wpilibj
.DoubleSolenoid
.Value
;
12 import edu
.wpi
.first
.wpilibj
.Encoder
;
13 import edu
.wpi
.first
.wpilibj
.I2C
;
14 import edu
.wpi
.first
.wpilibj
.RobotDrive
;
15 import edu
.wpi
.first
.wpilibj
.command
.PIDSubsystem
;
17 public class DriveTrain
extends PIDSubsystem
{
18 private static double pidOutput
= 0;
19 private static double encoderTolerance
= 8.0, gyroTolerance
= 5.0;
20 private int DRIVE_MODE
= 1;
22 private static final int MANUAL_MODE
= 1, ENCODER_MODE
= 2, GYRO_MODE
= 3;
24 private Encoder leftEncoder
, rightEncoder
;
25 private CANTalon frontLeft
, frontRight
, rearLeft
, rearRight
;
26 private RobotDrive robotDrive
;
29 private DoubleSolenoid leftGearPiston
, rightGearPiston
;
30 // Drivetrain specific constants that relate to the inches per pulse value for
32 private final static double WHEEL_DIAMETER
= 6.0; // in inches
33 private final static double PULSES_PER_ROTATION
= 256; // in pulses
34 private final static double OUTPUT_SPROCKET_DIAMETER
= 2.0; // in inches
35 private final static double WHEEL_SPROCKET_DIAMETER
= 3.5; // in inches
36 public final static double INCHES_PER_PULSE
= (((Math
.PI
)
37 * OUTPUT_SPROCKET_DIAMETER
/ PULSES_PER_ROTATION
)
38 / WHEEL_SPROCKET_DIAMETER
) * WHEEL_DIAMETER
;
40 // Drivetrain specific constants that relate to the PID controllers
41 private final static double Kp
= 1.0, Ki
= 0.0,
42 Kd
= 0.0 * (OUTPUT_SPROCKET_DIAMETER
/ PULSES_PER_ROTATION
)
43 / (WHEEL_SPROCKET_DIAMETER
) * WHEEL_DIAMETER
;
48 frontLeft
= new CANTalon(Constants
.DriveTrain
.FRONT_LEFT
);
49 frontRight
= new CANTalon(Constants
.DriveTrain
.FRONT_RIGHT
);
50 rearLeft
= new CANTalon(Constants
.DriveTrain
.REAR_LEFT
);
51 rearRight
= new CANTalon(Constants
.DriveTrain
.REAR_RIGHT
);
53 robotDrive
= new RobotDrive(frontLeft
, rearLeft
, frontRight
, rearRight
);
54 leftEncoder
= new Encoder(Constants
.DriveTrain
.ENCODER_LEFT_A
,
55 Constants
.DriveTrain
.ENCODER_LEFT_B
, false, EncodingType
.k4X
);
56 rightEncoder
= new Encoder(Constants
.DriveTrain
.ENCODER_RIGHT_A
,
57 Constants
.DriveTrain
.ENCODER_RIGHT_B
, false, EncodingType
.k4X
);
58 leftEncoder
.setDistancePerPulse(Constants
.DriveTrain
.INCHES_PER_PULSE
);
59 rightEncoder
.setDistancePerPulse(Constants
.DriveTrain
.INCHES_PER_PULSE
);
61 leftEncoder
.setDistancePerPulse(Constants
.DriveTrain
.INCHES_PER_PULSE
);
62 rightEncoder
.setDistancePerPulse(Constants
.DriveTrain
.INCHES_PER_PULSE
);
64 gyro
= new GyroLib(I2C
.Port
.kOnboard
, false);
66 DRIVE_MODE
= Constants
.DriveTrain
.ENCODER_MODE
;
71 leftGearPiston
= new DoubleSolenoid(Constants
.DriveTrain
.LEFT_FORWARD
,
72 +Constants
.DriveTrain
.LEFT_REVERSE
);
73 rightGearPiston
= new DoubleSolenoid(Constants
.DriveTrain
.RIGHT_FORWARD
,
74 Constants
.DriveTrain
.RIGHT_REVERSE
);
78 protected void initDefaultCommand() {
79 setDefaultCommand(new JoystickDrive());
82 public void printOutput() {
83 System
.out
.println("PIDOutput: " + pidOutput
);
86 private double getAvgEncoderDistance() {
87 return (leftEncoder
.getDistance() + rightEncoder
.getDistance()) / 2;
90 public boolean reachedTarget() {
91 if (this.onTarget()) {
103 public void resetEncoders() {
105 rightEncoder
.reset();
108 public Value
getLeftGearPistonValue() {
109 return leftGearPiston
.get();
112 public Value
getRightGearPistonValue() {
113 return rightGearPiston
.get();
116 public double getRightSpeed() {
117 return rightEncoder
.getRate(); // in inches per second
120 public double getLeftSpeed() {
121 return leftEncoder
.getRate(); // in inches per second
124 public double getSpeed() {
125 return (getLeftSpeed() + getRightSpeed()) / 2.0; // in inches per second
128 public double getRightDistance() {
129 return rightEncoder
.getDistance(); // in inches
132 public double getLeftDistance() {
133 return leftEncoder
.getDistance(); // in inches
136 public double getError() {
137 if (DRIVE_MODE
== Constants
.DriveTrain
.ENCODER_MODE
)
138 return Math
.abs(this.getSetpoint() - getAvgEncoderDistance());
140 return Math
.abs(this.getSetpoint() + getGyroAngle());
143 public double getGyroAngle() {
144 return gyro
.getRotationZ().getAngle();
147 public void resetGyro() {
151 public void printEncoder(int i
, int n
) {
153 System
.out
.println("Left: " + this.getLeftDistance());
154 System
.out
.println("Right: " + this.getRightDistance());
159 public void printGyroOutput() {
160 System
.out
.println("Gyro Angle" + -this.getGyroAngle());
163 public double getOutput() {
167 public void updatePID() {
168 if (DRIVE_MODE
== Constants
.DriveTrain
.ENCODER_MODE
)
169 this.getPIDController().setPID(kp
, ki
, kd
);
171 this.getPIDController().setPID(gp
, gd
, gi
);
174 public CANTalon
getFrontLeft() {
178 public CANTalon
getFrontRight() {
182 public CANTalon
getRearLeft() {
186 public CANTalon
getRearRight() {
190 public int getMode() {
195 protected void usePIDOutput(double output
) {
198 if (DRIVE_MODE
== Constants
.DriveTrain
.ENCODER_MODE
) {
199 double drift
= this.getLeftDistance() - this.getRightDistance();
200 if (Math
.abs(output
) > 0 && Math
.abs(output
) < 0.3)
201 output
= Math
.signum(output
) * 0.3;
203 right
= output
+ drift
* kp
/ 10;
205 else if (DRIVE_MODE
== Constants
.DriveTrain
.GYRO_MODE
) {
214 protected double returnPIDInput() {
215 return sensorFeedback();
218 private double sensorFeedback() {
219 if (DRIVE_MODE
== Constants
.DriveTrain
.ENCODER_MODE
)
220 return getAvgEncoderDistance();
221 else if (DRIVE_MODE
== Constants
.DriveTrain
.GYRO_MODE
)
222 return -this.getGyroAngle();
223 // counterclockwise is positive on joystick but we want it to be negative
228 public void drive(double left
, double right
) {
229 robotDrive
.tankDrive(-left
, -right
);
230 // dunno why but inverted drive (- values is forward)
233 public void driveDistance(double dist
, double maxTimeOut
) {
234 dist
= MathLib
.constrain(dist
, -100, 100);
239 public void setEncoderPID() {
240 DRIVE_MODE
= Constants
.DriveTrain
.ENCODER_MODE
;
242 this.setAbsoluteTolerance(encoderTolerance
);
243 this.setOutputRange(-1.0, 1.0);
244 this.setInputRange(-200.0, 200.0);
248 private void setGyroPID() {
249 DRIVE_MODE
= Constants
.DriveTrain
.GYRO_MODE
;
251 this.getPIDController().setPID(gp
, gi
, gd
);
253 this.setAbsoluteTolerance(gyroTolerance
);
254 this.setOutputRange(-1.0, 1.0);
255 this.setInputRange(-360.0, 360.0);
259 public void turnAngle(double angle
) {
260 angle
= MathLib
.constrain(angle
, -360, 360);
265 public void setMotorSpeeds(double left
, double right
) {
266 // positive setpoint to left side makes it go backwards
267 // positive setpoint to right side makes it go forwards.
268 frontLeft
.set(-left
);
270 frontRight
.set(right
);
271 rearRight
.set(right
);
274 private static double kp
= 0.013, ki
= 0.000015, kd
= -0.002;
275 private static double gp
= 0.018, gi
= 0.000015, gd
= 0;