import org.usfirst.frc.team3501.robot.Constants;
import org.usfirst.frc.team3501.robot.commands.driving.JoystickDrive;
-import org.usfirst.frc.team3501.robot.utils.BNO055;
import com.ctre.CANTalon;
+import edu.wpi.first.wpilibj.ADXRS450_Gyro;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.RobotDrive;
import edu.wpi.first.wpilibj.command.Subsystem;
public class DriveTrain extends Subsystem {
public static double driveP = 0.008, driveI = 0.001, driveD = -0.002;
- public static double defaultGyroP = 0.009, defaultGyroI = 0.00000,
+ public static double defaultGyroP = 0.006, defaultGyroI = 0.00000,
defaultGyroD = -0.000;
private double gyroZero = 0;
private final RobotDrive robotDrive;
private final Encoder leftEncoder, rightEncoder;
- private BNO055 imu;
+ private ADXRS450_Gyro imu;
private DriveTrain() {
// MOTOR CONTROLLERS
// ROBOT DRIVE
robotDrive = new RobotDrive(frontLeft, rearLeft, frontRight, rearRight);
+
+ this.imu = new ADXRS450_Gyro(Constants.DriveTrain.GYRO_PORT);
}
public static DriveTrain getDriveTrain() {
setMotorValues(0, 0);
}
- public double getFrontLeftMotorVal() {
- return frontLeft.get();
- }
-
- public double getFrontRightMotorVal() {
- return frontRight.get();
- }
-
- public double getRearLeftMotorVal() {
- return frontLeft.get();
+ public double getLeftMotorVal() {
+ return (frontLeft.get() + rearLeft.get()) / 2;
}
- public double getRearRightMotorVal() {
- return frontLeft.get();
+ public double getRightMotorVal() {
+ return (frontRight.get() + rearRight.get()) / 2;
}
// ENCODER METHODS
return rightEncoder.getDistance();
}
+ public void printEncoderOutput() {
+ // System.out.println("left: " + getLeftEncoderDistance());
+ // System.out.println("right: " + getRightEncoderDistance());
+ System.out.println(getAvgEncoderDistance());
+ }
+
public double getAvgEncoderDistance() {
return (leftEncoder.getDistance() + rightEncoder.getDistance()) / 2;
}
// ------Gyro------//
public double getAngle() {
- if (!this.imu.isInitialized())
- return -1;
- return this.imu.getHeading() - this.gyroZero;
+ return this.imu.getAngle() - this.gyroZero;
}
public void resetGyro() {
this.gyroZero = this.getAngle();
-
}
public double getZeroAngle() {