X-Git-Url: http://challenge-bot.com/repos/?p=3501%2F2017steamworks;a=blobdiff_plain;f=src%2Forg%2Fusfirst%2Ffrc%2Fteam3501%2Frobot%2Fsubsystems%2FDriveTrain.java;h=ba5392a62075ba75f66adfa032e68391fb4a84a7;hp=364340e106f2901ab65720f71d0f402df0aa950d;hb=e12d6901671044dfcf7eb0380c8193ec69bbc63d;hpb=0788fd3df6f9297dd1d22d41acb4f6c23ac9e8c4 diff --git a/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java b/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java index 364340e..ba5392a 100644 --- a/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java +++ b/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java @@ -2,6 +2,7 @@ package org.usfirst.frc.team3501.robot.subsystems; 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; @@ -10,6 +11,11 @@ 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, + defaultGyroD = -0.000; + private double gyroZero = 0; + public static final double WHEEL_DIAMETER = 6; // inches public static final int ENCODER_PULSES_PER_REVOLUTION = 256; public static final double INCHES_PER_PULSE = WHEEL_DIAMETER * Math.PI @@ -20,6 +26,8 @@ public class DriveTrain extends Subsystem { private final RobotDrive robotDrive; private final Encoder leftEncoder, rightEncoder; + private BNO055 imu; + private DriveTrain() { // MOTOR CONTROLLERS frontLeft = new CANTalon(Constants.DriveTrain.FRONT_LEFT); @@ -111,6 +119,22 @@ public class DriveTrain extends Subsystem { return (getLeftSpeed() + getRightSpeed()) / 2.0; } + // ------Gyro------// + public double getAngle() { + if (!this.imu.isInitialized()) + return -1; + return this.imu.getHeading() - this.gyroZero; + } + + public void resetGyro() { + this.gyroZero = this.getAngle(); + + } + + public double getZeroAngle() { + return this.gyroZero; + } + @Override protected void initDefaultCommand() { setDefaultCommand(new JoystickDrive());