package org.usfirst.frc.team3501.robot.subsystems;
import org.usfirst.frc.team3501.robot.Constants;
-import org.usfirst.frc.team3501.robot.GyroLib;
-import org.usfirst.frc.team3501.robot.MathLib;
import org.usfirst.frc.team3501.robot.commands.driving.JoystickDrive;
import edu.wpi.first.wpilibj.CANTalon;
import edu.wpi.first.wpilibj.DoubleSolenoid;
import edu.wpi.first.wpilibj.DoubleSolenoid.Value;
import edu.wpi.first.wpilibj.Encoder;
-import edu.wpi.first.wpilibj.I2C;
import edu.wpi.first.wpilibj.RobotDrive;
import edu.wpi.first.wpilibj.command.PIDSubsystem;
public class DriveTrain extends PIDSubsystem {
- private static double kp = 0.013, ki = 0.000015, kd = -0.002;
- private static double gp = 0.018, gi = 0.000015, gd = 0;
+ private boolean outputFlipped = false;
private static double pidOutput = 0;
- private static double encoderTolerance = 8.0, gyroTolerance = 5.0;
- private int DRIVE_MODE = 1;
-
- private static final int MANUAL_MODE = 1, ENCODER_MODE = 2, GYRO_MODE = 3;
private Encoder leftEncoder, rightEncoder;
- public static Lidar leftLidar;
- public static Lidar rightLidar;
-
private CANTalon frontLeft, frontRight, rearLeft, rearRight;
private RobotDrive robotDrive;
- private GyroLib gyro;
private DoubleSolenoid leftGearPiston, rightGearPiston;
+
// Drivetrain specific constants that relate to the inches per pulse value for
// the encoders
- private final static double WHEEL_DIAMETER = 6.0; // in inches
- private final static double PULSES_PER_ROTATION = 256; // in pulses
- private final static double OUTPUT_SPROCKET_DIAMETER = 2.0; // in inches
- private final static double WHEEL_SPROCKET_DIAMETER = 3.5; // in inches
- public final static double INCHES_PER_PULSE = (((Math.PI)
- * OUTPUT_SPROCKET_DIAMETER / PULSES_PER_ROTATION)
- / WHEEL_SPROCKET_DIAMETER) * WHEEL_DIAMETER;
-
- // Drivetrain specific constants that relate to the PID controllers
- private final static double Kp = 1.0, Ki = 0.0,
- Kd = 0.0 * (OUTPUT_SPROCKET_DIAMETER / PULSES_PER_ROTATION)
- / (WHEEL_SPROCKET_DIAMETER) * WHEEL_DIAMETER;
public DriveTrain() {
- super(kp, ki, kd);
+ super(Constants.DriveTrain.kp, Constants.DriveTrain.ki,
+ Constants.DriveTrain.kd);
frontLeft = new CANTalon(Constants.DriveTrain.FRONT_LEFT);
frontRight = new CANTalon(Constants.DriveTrain.FRONT_RIGHT);
robotDrive = new RobotDrive(frontLeft, rearLeft, frontRight, rearRight);
- leftLidar = new Lidar(I2C.Port.kOnboard);
- rightLidar = new Lidar(I2C.Port.kOnboard); // TODO: find port for second
- // lidar
leftEncoder = new Encoder(Constants.DriveTrain.ENCODER_LEFT_A,
Constants.DriveTrain.ENCODER_LEFT_B, false, EncodingType.k4X);
rightEncoder = new Encoder(Constants.DriveTrain.ENCODER_RIGHT_A,
leftEncoder.setDistancePerPulse(Constants.DriveTrain.INCHES_PER_PULSE);
rightEncoder.setDistancePerPulse(Constants.DriveTrain.INCHES_PER_PULSE);
- gyro = new GyroLib(I2C.Port.kOnboard, false);
-
- DRIVE_MODE = Constants.DriveTrain.ENCODER_MODE;
- setEncoderPID();
this.disable();
- gyro.start();
- leftGearPiston = new DoubleSolenoid(Constants.DriveTrain.LEFT_FORWARD,
- +Constants.DriveTrain.LEFT_REVERSE);
- rightGearPiston = new DoubleSolenoid(Constants.DriveTrain.RIGHT_FORWARD,
- Constants.DriveTrain.RIGHT_REVERSE);
+ leftGearPiston = new DoubleSolenoid(Constants.DriveTrain.LEFT_MODULE,
+ Constants.DriveTrain.LEFT_FORWARD, Constants.DriveTrain.LEFT_REVERSE);
+ rightGearPiston = new DoubleSolenoid(Constants.DriveTrain.RIGHT_MODULE,
+ Constants.DriveTrain.RIGHT_FORWARD, Constants.DriveTrain.RIGHT_REVERSE);
}
@Override
setDefaultCommand(new JoystickDrive());
}
+ // Print tne PID Output
public void printOutput() {
System.out.println("PIDOutput: " + pidOutput);
}
return (leftEncoder.getDistance() + rightEncoder.getDistance()) / 2;
}
+ // Whether or not the PID Controller thinks we have reached the target
+ // setpoint
public boolean reachedTarget() {
if (this.onTarget()) {
this.disable();
rightEncoder.reset();
}
- public double getLeftLidarDistance() {
- return leftLidar.pidGet();
- }
-
- public double getRightLidarDistance() {
- return rightLidar.pidGet();
- }
-
public double getRightSpeed() {
return rightEncoder.getRate(); // in inches per second
}
return leftEncoder.getDistance(); // in inches
}
+ // Get error between the setpoint of PID Controller and the current state of
+ // the robot
public double getError() {
- if (DRIVE_MODE == Constants.DriveTrain.ENCODER_MODE)
- return Math.abs(this.getSetpoint() - getAvgEncoderDistance());
- else
- return Math.abs(this.getSetpoint() + getGyroAngle());
- }
-
- public double getGyroAngle() {
- return gyro.getRotationZ().getAngle();
- }
-
- public void resetGyro() {
- gyro.reset();
+ return Math.abs(this.getSetpoint() - getAvgEncoderDistance());
}
public void printEncoder(int i, int n) {
}
}
- public void printGyroOutput() {
- System.out.println("Gyro Angle" + -this.getGyroAngle());
- }
-
+ /*
+ * returns the PID output that is returned by the PID Controller
+ */
public double getOutput() {
return pidOutput;
}
+ // Updates the PID constants based on which control mode is being used
public void updatePID() {
- if (DRIVE_MODE == Constants.DriveTrain.ENCODER_MODE)
- this.getPIDController().setPID(kp, ki, kd);
- else
- this.getPIDController().setPID(gp, gd, gi);
+ this.getPIDController().setPID(Constants.DriveTrain.kp,
+ Constants.DriveTrain.ki, Constants.DriveTrain.kd);
}
public CANTalon getFrontLeft() {
return rearRight;
}
- public int getMode() {
- return DRIVE_MODE;
- }
-
+ /*
+ * Method is a required method that the PID Subsystem uses to return the
+ * calculated PID value to the driver
+ *
+ * @param Gives the user the output from the PID algorithm that is calculated
+ * internally
+ *
+ * Body: Uses the output, does some filtering and drives the robot
+ */
@Override
protected void usePIDOutput(double output) {
double left = 0;
double right = 0;
- if (DRIVE_MODE == Constants.DriveTrain.ENCODER_MODE) {
- double drift = this.getLeftDistance() - this.getRightDistance();
- if (Math.abs(output) > 0 && Math.abs(output) < 0.3)
- output = Math.signum(output) * 0.3;
- left = output;
- right = output + drift * kp / 10;
- } else if (DRIVE_MODE == Constants.DriveTrain.GYRO_MODE) {
- left = output;
- right = -output;
- }
+ double drift = this.getLeftDistance() - this.getRightDistance();
+ if (Math.abs(output) > 0 && Math.abs(output) < 0.3)
+ output = Math.signum(output) * 0.3;
+ left = output;
+ right = output + drift * Constants.DriveTrain.kp / 10;
drive(left, right);
pidOutput = output;
}
return sensorFeedback();
}
+ /*
+ * Checks the drive mode
+ *
+ * @return the current state of the robot in each state Average distance from
+ * both sides of tank drive for Encoder Mode Angle from the gyro in GYRO_MODE
+ */
private double sensorFeedback() {
- if (DRIVE_MODE == Constants.DriveTrain.ENCODER_MODE)
- return getAvgEncoderDistance();
- else if (DRIVE_MODE == Constants.DriveTrain.GYRO_MODE)
- return -this.getGyroAngle();
- // counterclockwise is positive on joystick but we want it to be negative
- else
- return 0;
+ return getAvgEncoderDistance();
}
+ /*
+ * @param left and right setpoints to set to the left and right side of tank
+ * inverted is for Logan, wants the robot to invert all controls left = right
+ * and right = left negative input is required for the regular rotation
+ * because RobotDrive tankdrive method drives inverted
+ */
public void drive(double left, double right) {
robotDrive.tankDrive(-left, -right);
- // dunno why but inverted drive (- values is forward)
- }
-
- public void driveDistance(double dist, double maxTimeOut) {
- dist = MathLib.constrain(dist, -100, 100);
- setEncoderPID();
- setSetpoint(dist);
- }
-
- public void setEncoderPID() {
- DRIVE_MODE = Constants.DriveTrain.ENCODER_MODE;
- this.updatePID();
- this.setAbsoluteTolerance(encoderTolerance);
- this.setOutputRange(-1.0, 1.0);
- this.setInputRange(-200.0, 200.0);
- this.enable();
- }
-
- private void setGyroPID() {
- DRIVE_MODE = Constants.DriveTrain.GYRO_MODE;
- this.updatePID();
- this.getPIDController().setPID(gp, gi, gd);
-
- this.setAbsoluteTolerance(gyroTolerance);
- this.setOutputRange(-1.0, 1.0);
- this.setInputRange(-360.0, 360.0);
- this.enable();
- }
-
- public void turnAngle(double angle) {
- angle = MathLib.constrain(angle, -360, 360);
- setGyroPID();
- setSetpoint(angle);
}
public void setMotorSpeeds(double left, double right) {
rearRight.set(right);
}
- public Value getLeftGearPistonValue() {
- return leftGearPiston.get();
- }
-
- public Value getRightGearPistonValue() {
- return rightGearPiston.get();
+ /**
+ * @return a value that is the current setpoint for the piston (kReverse or
+ * kForward)
+ */
+ public Value getGearPistonValue() {
+ return leftGearPiston.get(); // Pistons should always be in the same state
}
+ /**
+ * Changes the ball shift gear assembly to high
+ */
public void setHighGear() {
changeGear(Constants.DriveTrain.HIGH_GEAR);
}
+ /**
+ * Changes the ball shift gear assembly to low
+ */
public void setLowGear() {
changeGear(Constants.DriveTrain.LOW_GEAR);
}
+ /**
+ * Changes the gear to a DoubleSolenoid.Value
+ */
public void changeGear(DoubleSolenoid.Value gear) {
leftGearPiston.set(gear);
rightGearPiston.set(gear);
}
+
+ /**
+ * Switches drivetrain gears from high to low or low to high
+ */
+ public void switchGear() {
+ Value currentValue = getGearPistonValue();
+ Value setValue = (currentValue == Constants.DriveTrain.HIGH_GEAR) ? Constants.DriveTrain.LOW_GEAR
+ : Constants.DriveTrain.HIGH_GEAR;
+ changeGear(setValue);
+ }
+
+ /**
+ * Toggle whether the motor outputs are flipped, effectively switching which
+ * side of the robot is the front.
+ */
+ public void toggleFlipped() {
+ outputFlipped = !outputFlipped;
+ }
+
+ public boolean isFlipped() {
+ return outputFlipped;
+ }
+
}