finish implement driveDistance and TurnForAngle using PID algorithm
[3501/2017steamworks] / src / org / usfirst / frc / team3501 / robot / subsystems / DriveTrain.java
CommitLineData
38a404b3
KZ
1package org.usfirst.frc.team3501.robot.subsystems;
2
3import org.usfirst.frc.team3501.robot.Constants;
5483fde9 4import org.usfirst.frc.team3501.robot.commands.driving.JoystickDrive;
e12d6901 5import org.usfirst.frc.team3501.robot.utils.BNO055;
04f2cb52 6
a1c76caf
CZ
7import com.ctre.CANTalon;
8
fa4e4a97 9import edu.wpi.first.wpilibj.Encoder;
8e4c083c 10import edu.wpi.first.wpilibj.I2C.Port;
ccbc35ae 11import edu.wpi.first.wpilibj.RobotDrive;
38a404b3
KZ
12import edu.wpi.first.wpilibj.command.Subsystem;
13
14public class DriveTrain extends Subsystem {
e12d6901 15 public static double driveP = 0.008, driveI = 0.001, driveD = -0.002;
f0a71840 16 public static double defaultGyroP = 0.006, defaultGyroI = 0.00000,
e12d6901
CZ
17 defaultGyroD = -0.000;
18 private double gyroZero = 0;
19
b634ebbc
CZ
20 public static final double WHEEL_DIAMETER = 6; // inches
21 public static final int ENCODER_PULSES_PER_REVOLUTION = 256;
22 public static final double INCHES_PER_PULSE = WHEEL_DIAMETER * Math.PI
23 / ENCODER_PULSES_PER_REVOLUTION;
24
cc42bd52
ME
25 private static DriveTrain driveTrain;
26 private final CANTalon frontLeft, frontRight, rearLeft, rearRight;
27 private final RobotDrive robotDrive;
28 private final Encoder leftEncoder, rightEncoder;
29
e12d6901
CZ
30 private BNO055 imu;
31
cc42bd52
ME
32 private DriveTrain() {
33 // MOTOR CONTROLLERS
34 frontLeft = new CANTalon(Constants.DriveTrain.FRONT_LEFT);
35 frontRight = new CANTalon(Constants.DriveTrain.FRONT_RIGHT);
36 rearLeft = new CANTalon(Constants.DriveTrain.REAR_LEFT);
37 rearRight = new CANTalon(Constants.DriveTrain.REAR_RIGHT);
38
39 // ENCODERS
40 leftEncoder = new Encoder(Constants.DriveTrain.ENCODER_LEFT_A,
3e2738c4 41 Constants.DriveTrain.ENCODER_LEFT_B, false, Encoder.EncodingType.k4X);
cc42bd52 42 rightEncoder = new Encoder(Constants.DriveTrain.ENCODER_RIGHT_A,
3e2738c4 43 Constants.DriveTrain.ENCODER_RIGHT_B, false, Encoder.EncodingType.k4X);
cc42bd52 44
b634ebbc
CZ
45 leftEncoder.setDistancePerPulse(INCHES_PER_PULSE);
46 rightEncoder.setDistancePerPulse(INCHES_PER_PULSE);
cc42bd52
ME
47
48 // ROBOT DRIVE
49 robotDrive = new RobotDrive(frontLeft, rearLeft, frontRight, rearRight);
8e4c083c
CZ
50
51 this.imu = BNO055.getInstance(BNO055.opmode_t.OPERATION_MODE_IMUPLUS,
52 BNO055.vector_type_t.VECTOR_EULER, Port.kOnboard, (byte) 0x28);
53 gyroZero = imu.getHeading();
cc42bd52
ME
54 }
55
56 public static DriveTrain getDriveTrain() {
57 if (driveTrain == null) {
58 driveTrain = new DriveTrain();
59 }
60 return driveTrain;
61 }
62
63 // DRIVE METHODS
64 public void setMotorValues(final double left, final double right) {
65 frontLeft.set(left);
66 rearLeft.set(left);
67
b081e34b
ME
68 frontRight.set(-right);
69 rearRight.set(-right);
cc42bd52
ME
70 }
71
72 public void joystickDrive(final double thrust, final double twist) {
b081e34b 73 robotDrive.arcadeDrive(thrust, twist, true);
cc42bd52
ME
74 }
75
76 public void stop() {
77 setMotorValues(0, 0);
78 }
79
f0a71840
CZ
80 public double getLeftMotorVal() {
81 return (frontLeft.get() + rearLeft.get()) / 2;
cc42bd52
ME
82 }
83
f0a71840
CZ
84 public double getRightMotorVal() {
85 return (frontRight.get() + rearRight.get()) / 2;
cc42bd52
ME
86 }
87
cc42bd52
ME
88 // ENCODER METHODS
89
3a5d9ac7 90 public double getLeftEncoderDistance() {
cc42bd52
ME
91 return leftEncoder.getDistance();
92 }
93
3a5d9ac7 94 public double getRightEncoderDistance() {
cc42bd52
ME
95 return rightEncoder.getDistance();
96 }
97
8e4c083c 98 public void printEncoderOutput() {
f0a71840
CZ
99 // System.out.println("left: " + getLeftEncoderDistance());
100 // System.out.println("right: " + getRightEncoderDistance());
101 System.out.println(getAvgEncoderDistance());
8e4c083c
CZ
102 }
103
cc42bd52
ME
104 public double getAvgEncoderDistance() {
105 return (leftEncoder.getDistance() + rightEncoder.getDistance()) / 2;
106 }
107
108 public void resetEncoders() {
109 leftEncoder.reset();
110 rightEncoder.reset();
111 }
112
113 public double getLeftSpeed() {
114 return leftEncoder.getRate();
115 }
116
117 public double getRightSpeed() {
118 return rightEncoder.getRate();
119 }
120
121 public double getSpeed() {
122 return (getLeftSpeed() + getRightSpeed()) / 2.0;
123 }
124
e12d6901
CZ
125 // ------Gyro------//
126 public double getAngle() {
127 if (!this.imu.isInitialized())
128 return -1;
129 return this.imu.getHeading() - this.gyroZero;
130 }
131
132 public void resetGyro() {
133 this.gyroZero = this.getAngle();
134
135 }
136
137 public double getZeroAngle() {
138 return this.gyroZero;
139 }
140
cc42bd52
ME
141 @Override
142 protected void initDefaultCommand() {
143 setDefaultCommand(new JoystickDrive());
144 }
38a404b3
KZ
145
146}