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 kp
= 0.013, ki
= 0.000015, kd
= -0.002;
19 private static double gp
= 0.018, gi
= 0.000015, gd
= 0;
20 private static double pidOutput
= 0;
21 private static double encoderTolerance
= 8.0, gyroTolerance
= 5.0;
22 private int DRIVE_MODE
= 1;
24 private static final int MANUAL_MODE
= 1, ENCODER_MODE
= 2, GYRO_MODE
= 3;
26 private Encoder leftEncoder
, rightEncoder
;
27 private CANTalon frontLeft
, frontRight
, rearLeft
, rearRight
;
28 private RobotDrive robotDrive
;
31 private DoubleSolenoid leftGearPiston
, rightGearPiston
;
32 // Drivetrain specific constants that relate to the inches per pulse value for
34 private final static double WHEEL_DIAMETER
= 6.0; // in inches
35 private final static double PULSES_PER_ROTATION
= 256; // in pulses
36 private final static double OUTPUT_SPROCKET_DIAMETER
= 2.0; // in inches
37 private final static double WHEEL_SPROCKET_DIAMETER
= 3.5; // in inches
38 public final static double INCHES_PER_PULSE
= (((Math
.PI
)
39 * OUTPUT_SPROCKET_DIAMETER
/ PULSES_PER_ROTATION
)
40 / WHEEL_SPROCKET_DIAMETER
) * WHEEL_DIAMETER
;
42 // Drivetrain specific constants that relate to the PID controllers
43 private final static double Kp
= 1.0, Ki
= 0.0,
44 Kd
= 0.0 * (OUTPUT_SPROCKET_DIAMETER
/ PULSES_PER_ROTATION
)
45 / (WHEEL_SPROCKET_DIAMETER
) * WHEEL_DIAMETER
;
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
);
55 robotDrive
= new RobotDrive(frontLeft
, rearLeft
, frontRight
, rearRight
);
56 leftEncoder
= new Encoder(Constants
.DriveTrain
.ENCODER_LEFT_A
,
57 Constants
.DriveTrain
.ENCODER_LEFT_B
, false, EncodingType
.k4X
);
58 rightEncoder
= new Encoder(Constants
.DriveTrain
.ENCODER_RIGHT_A
,
59 Constants
.DriveTrain
.ENCODER_RIGHT_B
, false, EncodingType
.k4X
);
60 leftEncoder
.setDistancePerPulse(Constants
.DriveTrain
.INCHES_PER_PULSE
);
61 rightEncoder
.setDistancePerPulse(Constants
.DriveTrain
.INCHES_PER_PULSE
);
63 leftEncoder
.setDistancePerPulse(Constants
.DriveTrain
.INCHES_PER_PULSE
);
64 rightEncoder
.setDistancePerPulse(Constants
.DriveTrain
.INCHES_PER_PULSE
);
66 gyro
= new GyroLib(I2C
.Port
.kOnboard
, false);
68 DRIVE_MODE
= Constants
.DriveTrain
.ENCODER_MODE
;
73 leftGearPiston
= new DoubleSolenoid(Constants
.DriveTrain
.LEFT_FORWARD
,
74 +Constants
.DriveTrain
.LEFT_REVERSE
);
75 rightGearPiston
= new DoubleSolenoid(Constants
.DriveTrain
.RIGHT_FORWARD
,
76 Constants
.DriveTrain
.RIGHT_REVERSE
);
77 Constants
.DriveTrain
.inverted
= false;
81 protected void initDefaultCommand() {
82 setDefaultCommand(new JoystickDrive());
85 public void printOutput() {
86 System
.out
.println("PIDOutput: " + pidOutput
);
89 private double getAvgEncoderDistance() {
90 return (leftEncoder
.getDistance() + rightEncoder
.getDistance()) / 2;
93 public boolean reachedTarget() {
94 if (this.onTarget()) {
106 public void resetEncoders() {
108 rightEncoder
.reset();
111 public double getRightSpeed() {
112 return rightEncoder
.getRate(); // in inches per second
115 public double getLeftSpeed() {
116 return leftEncoder
.getRate(); // in inches per second
119 public double getSpeed() {
120 return (getLeftSpeed() + getRightSpeed()) / 2.0; // in inches per second
123 public double getRightDistance() {
124 return rightEncoder
.getDistance(); // in inches
127 public double getLeftDistance() {
128 return leftEncoder
.getDistance(); // in inches
131 public double getError() {
132 if (DRIVE_MODE
== Constants
.DriveTrain
.ENCODER_MODE
)
133 return Math
.abs(this.getSetpoint() - getAvgEncoderDistance());
135 return Math
.abs(this.getSetpoint() + getGyroAngle());
138 public double getGyroAngle() {
139 return gyro
.getRotationZ().getAngle();
142 public void resetGyro() {
146 public void printEncoder(int i
, int n
) {
148 System
.out
.println("Left: " + this.getLeftDistance());
149 System
.out
.println("Right: " + this.getRightDistance());
154 public void printGyroOutput() {
155 System
.out
.println("Gyro Angle" + -this.getGyroAngle());
158 public double getOutput() {
162 public void updatePID() {
163 if (DRIVE_MODE
== Constants
.DriveTrain
.ENCODER_MODE
)
164 this.getPIDController().setPID(kp
, ki
, kd
);
166 this.getPIDController().setPID(gp
, gd
, gi
);
169 public CANTalon
getFrontLeft() {
173 public CANTalon
getFrontRight() {
177 public CANTalon
getRearLeft() {
181 public CANTalon
getRearRight() {
185 public int getMode() {
190 protected void usePIDOutput(double output
) {
193 if (DRIVE_MODE
== Constants
.DriveTrain
.ENCODER_MODE
) {
194 double drift
= this.getLeftDistance() - this.getRightDistance();
195 if (Math
.abs(output
) > 0 && Math
.abs(output
) < 0.3)
196 output
= Math
.signum(output
) * 0.3;
198 right
= output
+ drift
* kp
/ 10;
200 else if (DRIVE_MODE
== Constants
.DriveTrain
.GYRO_MODE
) {
209 protected double returnPIDInput() {
210 return sensorFeedback();
213 private double sensorFeedback() {
214 if (DRIVE_MODE
== Constants
.DriveTrain
.ENCODER_MODE
)
215 return getAvgEncoderDistance();
216 else if (DRIVE_MODE
== Constants
.DriveTrain
.GYRO_MODE
)
217 return -this.getGyroAngle();
218 // counterclockwise is positive on joystick but we want it to be negative
223 public void drive(double left
, double right
) {
224 // dunno why but inverted drive (- values is forward)
225 if (!Constants
.DriveTrain
.inverted
)
226 robotDrive
.tankDrive(-left
,
229 robotDrive
.tankDrive(right
, left
);
232 public void driveDistance(double dist
, double maxTimeOut
) {
233 dist
= MathLib
.constrain(dist
, -100, 100);
238 public void setEncoderPID() {
239 DRIVE_MODE
= Constants
.DriveTrain
.ENCODER_MODE
;
241 this.setAbsoluteTolerance(encoderTolerance
);
242 this.setOutputRange(-1.0, 1.0);
243 this.setInputRange(-200.0, 200.0);
247 private void setGyroPID() {
248 DRIVE_MODE
= Constants
.DriveTrain
.GYRO_MODE
;
250 this.getPIDController().setPID(gp
, gi
, gd
);
252 this.setAbsoluteTolerance(gyroTolerance
);
253 this.setOutputRange(-1.0, 1.0);
254 this.setInputRange(-360.0, 360.0);
258 public void turnAngle(double angle
) {
259 angle
= MathLib
.constrain(angle
, -360, 360);
264 public void setMotorSpeeds(double left
, double right
) {
265 // positive setpoint to left side makes it go backwards
266 // positive setpoint to right side makes it go forwards.
267 frontLeft
.set(-left
);
269 frontRight
.set(right
);
270 rearRight
.set(right
);
273 public Value
getLeftGearPistonValue() {
274 return leftGearPiston
.get();
277 public Value
getRightGearPistonValue() {
278 return rightGearPiston
.get();
281 public void setHighGear() {
282 changeGear(Constants
.DriveTrain
.HIGH_GEAR
);
285 public void setLowGear() {
286 changeGear(Constants
.DriveTrain
.LOW_GEAR
);
289 public void changeGear(DoubleSolenoid
.Value gear
) {
290 leftGearPiston
.set(gear
);
291 rightGearPiston
.set(gear
);