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
;
28 public static Lidar leftLidar
;
29 public static Lidar rightLidar
;
31 private CANTalon frontLeft
, frontRight
, rearLeft
, rearRight
;
32 private RobotDrive robotDrive
;
35 private DoubleSolenoid leftGearPiston
, rightGearPiston
;
36 // Drivetrain specific constants that relate to the inches per pulse value for
38 private final static double WHEEL_DIAMETER
= 6.0; // in inches
39 private final static double PULSES_PER_ROTATION
= 256; // in pulses
40 private final static double OUTPUT_SPROCKET_DIAMETER
= 2.0; // in inches
41 private final static double WHEEL_SPROCKET_DIAMETER
= 3.5; // in inches
42 public final static double INCHES_PER_PULSE
= (((Math
.PI
)
43 * OUTPUT_SPROCKET_DIAMETER
/ PULSES_PER_ROTATION
)
44 / WHEEL_SPROCKET_DIAMETER
) * WHEEL_DIAMETER
;
46 // Drivetrain specific constants that relate to the PID controllers
47 private final static double Kp
= 1.0, Ki
= 0.0,
48 Kd
= 0.0 * (OUTPUT_SPROCKET_DIAMETER
/ PULSES_PER_ROTATION
)
49 / (WHEEL_SPROCKET_DIAMETER
) * WHEEL_DIAMETER
;
54 frontLeft
= new CANTalon(Constants
.DriveTrain
.FRONT_LEFT
);
55 frontRight
= new CANTalon(Constants
.DriveTrain
.FRONT_RIGHT
);
56 rearLeft
= new CANTalon(Constants
.DriveTrain
.REAR_LEFT
);
57 rearRight
= new CANTalon(Constants
.DriveTrain
.REAR_RIGHT
);
59 robotDrive
= new RobotDrive(frontLeft
, rearLeft
, frontRight
, rearRight
);
61 leftLidar
= new Lidar(I2C
.Port
.kOnboard
);
62 rightLidar
= new Lidar(I2C
.Port
.kOnboard
); // TODO: find port for second
64 leftEncoder
= new Encoder(Constants
.DriveTrain
.ENCODER_LEFT_A
,
65 Constants
.DriveTrain
.ENCODER_LEFT_B
, false, EncodingType
.k4X
);
66 rightEncoder
= new Encoder(Constants
.DriveTrain
.ENCODER_RIGHT_A
,
67 Constants
.DriveTrain
.ENCODER_RIGHT_B
, false, EncodingType
.k4X
);
68 leftEncoder
.setDistancePerPulse(Constants
.DriveTrain
.INCHES_PER_PULSE
);
69 rightEncoder
.setDistancePerPulse(Constants
.DriveTrain
.INCHES_PER_PULSE
);
71 leftEncoder
.setDistancePerPulse(Constants
.DriveTrain
.INCHES_PER_PULSE
);
72 rightEncoder
.setDistancePerPulse(Constants
.DriveTrain
.INCHES_PER_PULSE
);
74 gyro
= new GyroLib(I2C
.Port
.kOnboard
, false);
76 DRIVE_MODE
= Constants
.DriveTrain
.ENCODER_MODE
;
81 leftGearPiston
= new DoubleSolenoid(Constants
.DriveTrain
.LEFT_FORWARD
,
82 +Constants
.DriveTrain
.LEFT_REVERSE
);
83 rightGearPiston
= new DoubleSolenoid(Constants
.DriveTrain
.RIGHT_FORWARD
,
84 Constants
.DriveTrain
.RIGHT_REVERSE
);
88 protected void initDefaultCommand() {
89 setDefaultCommand(new JoystickDrive());
92 public void printOutput() {
93 System
.out
.println("PIDOutput: " + pidOutput
);
96 private double getAvgEncoderDistance() {
97 return (leftEncoder
.getDistance() + rightEncoder
.getDistance()) / 2;
100 public boolean reachedTarget() {
101 if (this.onTarget()) {
113 public void resetEncoders() {
115 rightEncoder
.reset();
118 public double getLeftLidarDistance() {
119 return leftLidar
.pidGet();
122 public double getsRightLidarDistance() {
123 return rightLidar
.pidGet();
126 public double getRightSpeed() {
127 return rightEncoder
.getRate(); // in inches per second
130 public double getLeftSpeed() {
131 return leftEncoder
.getRate(); // in inches per second
134 public double getSpeed() {
135 return (getLeftSpeed() + getRightSpeed()) / 2.0; // in inches per second
138 public double getRightDistance() {
139 return rightEncoder
.getDistance(); // in inches
142 public double getLeftDistance() {
143 return leftEncoder
.getDistance(); // in inches
146 public double getError() {
147 if (DRIVE_MODE
== Constants
.DriveTrain
.ENCODER_MODE
)
148 return Math
.abs(this.getSetpoint() - getAvgEncoderDistance());
150 return Math
.abs(this.getSetpoint() + getGyroAngle());
153 public double getGyroAngle() {
154 return gyro
.getRotationZ().getAngle();
157 public void resetGyro() {
161 public void printEncoder(int i
, int n
) {
163 System
.out
.println("Left: " + this.getLeftDistance());
164 System
.out
.println("Right: " + this.getRightDistance());
169 public void printGyroOutput() {
170 System
.out
.println("Gyro Angle" + -this.getGyroAngle());
173 public double getOutput() {
177 public void updatePID() {
178 if (DRIVE_MODE
== Constants
.DriveTrain
.ENCODER_MODE
)
179 this.getPIDController().setPID(kp
, ki
, kd
);
181 this.getPIDController().setPID(gp
, gd
, gi
);
184 public CANTalon
getFrontLeft() {
188 public CANTalon
getFrontRight() {
192 public CANTalon
getRearLeft() {
196 public CANTalon
getRearRight() {
200 public int getMode() {
205 protected void usePIDOutput(double output
) {
208 if (DRIVE_MODE
== Constants
.DriveTrain
.ENCODER_MODE
) {
209 double drift
= this.getLeftDistance() - this.getRightDistance();
210 if (Math
.abs(output
) > 0 && Math
.abs(output
) < 0.3)
211 output
= Math
.signum(output
) * 0.3;
213 right
= output
+ drift
* kp
/ 10;
214 } else if (DRIVE_MODE
== Constants
.DriveTrain
.GYRO_MODE
) {
223 protected double returnPIDInput() {
224 return sensorFeedback();
227 private double sensorFeedback() {
228 if (DRIVE_MODE
== Constants
.DriveTrain
.ENCODER_MODE
)
229 return getAvgEncoderDistance();
230 else if (DRIVE_MODE
== Constants
.DriveTrain
.GYRO_MODE
)
231 return -this.getGyroAngle();
232 // counterclockwise is positive on joystick but we want it to be negative
237 public void drive(double left
, double right
) {
238 robotDrive
.tankDrive(-left
, -right
);
239 // dunno why but inverted drive (- values is forward)
242 public void driveDistance(double dist
, double maxTimeOut
) {
243 dist
= MathLib
.constrain(dist
, -100, 100);
248 public void setEncoderPID() {
249 DRIVE_MODE
= Constants
.DriveTrain
.ENCODER_MODE
;
251 this.setAbsoluteTolerance(encoderTolerance
);
252 this.setOutputRange(-1.0, 1.0);
253 this.setInputRange(-200.0, 200.0);
257 private void setGyroPID() {
258 DRIVE_MODE
= Constants
.DriveTrain
.GYRO_MODE
;
260 this.getPIDController().setPID(gp
, gi
, gd
);
262 this.setAbsoluteTolerance(gyroTolerance
);
263 this.setOutputRange(-1.0, 1.0);
264 this.setInputRange(-360.0, 360.0);
268 public void turnAngle(double angle
) {
269 angle
= MathLib
.constrain(angle
, -360, 360);
274 public void setMotorSpeeds(double left
, double right
) {
275 // positive setpoint to left side makes it go backwards
276 // positive setpoint to right side makes it go forwards.
277 frontLeft
.set(-left
);
279 frontRight
.set(right
);
280 rearRight
.set(right
);
283 public Value
getLeftGearPistonValue() {
284 return leftGearPiston
.get();
287 public Value
getRightGearPistonValue() {
288 return rightGearPiston
.get();
291 public void setHighGear() {
292 changeGear(Constants
.DriveTrain
.HIGH_GEAR
);
295 public void setLowGear() {
296 changeGear(Constants
.DriveTrain
.LOW_GEAR
);
299 public void changeGear(DoubleSolenoid
.Value gear
) {
300 leftGearPiston
.set(gear
);
301 rightGearPiston
.set(gear
);