1 package org
.usfirst
.frc
.team3501
.robot
.subsystems
;
3 import org
.usfirst
.frc
.team3501
.robot
.Constants
;
4 import org
.usfirst
.frc
.team3501
.robot
.MathLib
;
5 import org
.usfirst
.frc
.team3501
.robot
.commands
.driving
.JoystickDrive
;
6 import org
.usfirst
.frc
.team3501
.robot
.sensors
.GyroLib
;
7 import org
.usfirst
.frc
.team3501
.robot
.sensors
.Lidar
;
9 import edu
.wpi
.first
.wpilibj
.CANTalon
;
10 import edu
.wpi
.first
.wpilibj
.CounterBase
.EncodingType
;
11 import edu
.wpi
.first
.wpilibj
.DoubleSolenoid
;
12 import edu
.wpi
.first
.wpilibj
.DoubleSolenoid
.Value
;
13 import edu
.wpi
.first
.wpilibj
.Encoder
;
14 import edu
.wpi
.first
.wpilibj
.I2C
;
15 import edu
.wpi
.first
.wpilibj
.RobotDrive
;
16 import edu
.wpi
.first
.wpilibj
.command
.PIDSubsystem
;
18 public class DriveTrain
extends PIDSubsystem
{
19 // Current Drive Mode Default Drive Mode is Manual
20 private int DRIVE_MODE
= 1;
21 private static double pidOutput
= 0;
23 private Encoder leftEncoder
, rightEncoder
;
25 public static Lidar lidar
;
27 private CANTalon frontLeft
, frontRight
, rearLeft
, rearRight
;
28 private RobotDrive robotDrive
;
31 private DoubleSolenoid leftGearPiston
, rightGearPiston
;
33 // Drivetrain specific constants that relate to the inches per pulse value for
37 super(Constants
.DriveTrain
.kp
, Constants
.DriveTrain
.ki
,
38 Constants
.DriveTrain
.kd
);
40 frontLeft
= new CANTalon(Constants
.DriveTrain
.FRONT_LEFT
);
41 frontRight
= new CANTalon(Constants
.DriveTrain
.FRONT_RIGHT
);
42 rearLeft
= new CANTalon(Constants
.DriveTrain
.REAR_LEFT
);
43 rearRight
= new CANTalon(Constants
.DriveTrain
.REAR_RIGHT
);
45 robotDrive
= new RobotDrive(frontLeft
, rearLeft
, frontRight
, rearRight
);
47 lidar
= new Lidar(I2C
.Port
.kOnboard
);
49 leftEncoder
= new Encoder(Constants
.DriveTrain
.ENCODER_LEFT_A
,
50 Constants
.DriveTrain
.ENCODER_LEFT_B
, false, EncodingType
.k4X
);
51 rightEncoder
= new Encoder(Constants
.DriveTrain
.ENCODER_RIGHT_A
,
52 Constants
.DriveTrain
.ENCODER_RIGHT_B
, false, EncodingType
.k4X
);
53 leftEncoder
.setDistancePerPulse(Constants
.DriveTrain
.INCHES_PER_PULSE
);
54 rightEncoder
.setDistancePerPulse(Constants
.DriveTrain
.INCHES_PER_PULSE
);
56 leftEncoder
.setDistancePerPulse(Constants
.DriveTrain
.INCHES_PER_PULSE
);
57 rightEncoder
.setDistancePerPulse(Constants
.DriveTrain
.INCHES_PER_PULSE
);
59 gyro
= new GyroLib(I2C
.Port
.kOnboard
, false);
61 DRIVE_MODE
= Constants
.DriveTrain
.ENCODER_MODE
;
66 leftGearPiston
= new DoubleSolenoid(Constants
.DriveTrain
.LEFT_FORWARD
,
67 Constants
.DriveTrain
.LEFT_REVERSE
);
68 rightGearPiston
= new DoubleSolenoid(Constants
.DriveTrain
.RIGHT_FORWARD
,
69 Constants
.DriveTrain
.RIGHT_REVERSE
);
70 Constants
.DriveTrain
.inverted
= false;
74 protected void initDefaultCommand() {
75 setDefaultCommand(new JoystickDrive());
78 // Print tne PID Output
79 public void printOutput() {
80 System
.out
.println("PIDOutput: " + pidOutput
);
83 private double getAvgEncoderDistance() {
84 return (leftEncoder
.getDistance() + rightEncoder
.getDistance()) / 2;
87 // Whether or not the PID Controller thinks we have reached the target
89 public boolean reachedTarget() {
90 if (this.onTarget()) {
102 public void resetEncoders() {
104 rightEncoder
.reset();
107 public double getLidarDistance() {
108 return lidar
.pidGet();
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 // Get error between the setpoint of PID Controller and the current state of
133 public double getError() {
134 if (DRIVE_MODE
== Constants
.DriveTrain
.ENCODER_MODE
)
135 return Math
.abs(this.getSetpoint() - getAvgEncoderDistance());
137 return Math
.abs(this.getSetpoint() + getGyroAngle());
140 public double getGyroAngle() {
141 return gyro
.getRotationZ().getAngle();
144 public void resetGyro() {
148 public void printEncoder(int i
, int n
) {
150 System
.out
.println("Left: " + this.getLeftDistance());
151 System
.out
.println("Right: " + this.getRightDistance());
156 public void printGyroOutput() {
157 System
.out
.println("Gyro Angle" + -this.getGyroAngle());
161 * returns the PID output that is returned by the PID Controller
163 public double getOutput() {
167 // Updates the PID constants based on which control mode is being used
168 public void updatePID() {
169 if (DRIVE_MODE
== Constants
.DriveTrain
.ENCODER_MODE
)
170 this.getPIDController().setPID(Constants
.DriveTrain
.kp
,
171 Constants
.DriveTrain
.ki
, Constants
.DriveTrain
.kd
);
173 this.getPIDController().setPID(Constants
.DriveTrain
.gp
,
174 Constants
.DriveTrain
.gd
, Constants
.DriveTrain
.gi
);
177 public CANTalon
getFrontLeft() {
181 public CANTalon
getFrontRight() {
185 public CANTalon
getRearLeft() {
189 public CANTalon
getRearRight() {
193 public int getMode() {
198 * Method is a required method that the PID Subsystem uses to return the
199 * calculated PID value to the driver
201 * @param Gives the user the output from the PID algorithm that is calculated
204 * Body: Uses the output, does some filtering and drives the robot
207 protected void usePIDOutput(double output
) {
210 if (DRIVE_MODE
== Constants
.DriveTrain
.ENCODER_MODE
) {
211 double drift
= this.getLeftDistance() - this.getRightDistance();
212 if (Math
.abs(output
) > 0 && Math
.abs(output
) < 0.3)
213 output
= Math
.signum(output
) * 0.3;
215 right
= output
+ drift
* Constants
.DriveTrain
.kp
/ 10;
216 } else if (DRIVE_MODE
== Constants
.DriveTrain
.GYRO_MODE
) {
225 protected double returnPIDInput() {
226 return sensorFeedback();
230 * Checks the drive mode
232 * @return the current state of the robot in each state Average distance from
233 * both sides of tank drive for Encoder Mode Angle from the gyro in GYRO_MODE
235 private double sensorFeedback() {
236 if (DRIVE_MODE
== Constants
.DriveTrain
.ENCODER_MODE
)
237 return getAvgEncoderDistance();
238 else if (DRIVE_MODE
== Constants
.DriveTrain
.GYRO_MODE
)
239 return -this.getGyroAngle();
240 // counterclockwise is positive on joystick but we want it to be negative
246 * @param left and right setpoints to set to the left and right side of tank
247 * inverted is for Logan, wants the robot to invert all controls left = right
248 * and right = left negative input is required for the regular rotation
249 * because RobotDrive tankdrive method drives inverted
251 public void drive(double left
, double right
) {
252 robotDrive
.tankDrive(-left
, -right
);
253 // dunno why but inverted drive (- values is forward)
254 if (!Constants
.DriveTrain
.inverted
)
255 robotDrive
.tankDrive(-left
, -right
);
257 robotDrive
.tankDrive(right
, left
);
261 * constrains the distance to within -100 and 100 since we aren't going to
262 * drive more than 100 inches
264 * Configure Encoder PID
266 * Sets the setpoint to the PID subsystem
268 public void driveDistance(double dist
, double maxTimeOut
) {
269 dist
= MathLib
.constrain(dist
, -100, 100);
275 * Sets the encoder mode Updates the PID constants sets the tolerance and sets
276 * output/input ranges Enables the PID controllers
278 public void setEncoderPID() {
279 DRIVE_MODE
= Constants
.DriveTrain
.ENCODER_MODE
;
281 this.setAbsoluteTolerance(Constants
.DriveTrain
.encoderTolerance
);
282 this.setOutputRange(-1.0, 1.0);
283 this.setInputRange(-200.0, 200.0);
288 * Sets the Gyro Mode Updates the PID constants, sets the tolerance and sets
289 * output/input ranges Enables the PID controllers
291 private void setGyroPID() {
292 DRIVE_MODE
= Constants
.DriveTrain
.GYRO_MODE
;
294 this.getPIDController().setPID(Constants
.DriveTrain
.gp
,
295 Constants
.DriveTrain
.gi
, Constants
.DriveTrain
.gd
);
297 this.setAbsoluteTolerance(Constants
.DriveTrain
.gyroTolerance
);
298 this.setOutputRange(-1.0, 1.0);
299 this.setInputRange(-360.0, 360.0);
304 * Turning method that should be used repeatedly in a command
306 * First constrains the angle to within -360 and 360 since that is as much as
309 * Configures Gyro PID and sets the setpoint as an angle
311 public void turnAngle(double angle
) {
312 angle
= MathLib
.constrain(angle
, -360, 360);
317 public void setMotorSpeeds(double left
, double right
) {
318 // positive setpoint to left side makes it go backwards
319 // positive setpoint to right side makes it go forwards.
320 frontLeft
.set(-left
);
322 frontRight
.set(right
);
323 rearRight
.set(right
);
327 * @return a value that is the current setpoint for the piston kReverse or
330 public Value
getLeftGearPistonValue() {
331 return leftGearPiston
.get();
335 * @return a value that is the current setpoint for the piston kReverse or
338 public Value
getRightGearPistonValue() {
339 return rightGearPiston
.get();
343 * Changes the ball shift gear assembly to high
345 public void setHighGear() {
346 changeGear(Constants
.DriveTrain
.HIGH_GEAR
);
350 * Changes the ball shift gear assembly to low
352 public void setLowGear() {
353 changeGear(Constants
.DriveTrain
.LOW_GEAR
);
357 * changes the gear to a DoubleSolenoid.Value
359 public void changeGear(DoubleSolenoid
.Value gear
) {
360 leftGearPiston
.set(gear
);
361 rightGearPiston
.set(gear
);