364340e106f2901ab65720f71d0f402df0aa950d
[3501/2017steamworks] / src / org / usfirst / frc / team3501 / robot / subsystems / DriveTrain.java
1 package org.usfirst.frc.team3501.robot.subsystems;
2
3 import org.usfirst.frc.team3501.robot.Constants;
4 import org.usfirst.frc.team3501.robot.commands.driving.JoystickDrive;
5
6 import com.ctre.CANTalon;
7
8 import edu.wpi.first.wpilibj.Encoder;
9 import edu.wpi.first.wpilibj.RobotDrive;
10 import edu.wpi.first.wpilibj.command.Subsystem;
11
12 public class DriveTrain extends Subsystem {
13 public static final double WHEEL_DIAMETER = 6; // inches
14 public static final int ENCODER_PULSES_PER_REVOLUTION = 256;
15 public static final double INCHES_PER_PULSE = WHEEL_DIAMETER * Math.PI
16 / ENCODER_PULSES_PER_REVOLUTION;
17
18 private static DriveTrain driveTrain;
19 private final CANTalon frontLeft, frontRight, rearLeft, rearRight;
20 private final RobotDrive robotDrive;
21 private final Encoder leftEncoder, rightEncoder;
22
23 private DriveTrain() {
24 // MOTOR CONTROLLERS
25 frontLeft = new CANTalon(Constants.DriveTrain.FRONT_LEFT);
26 frontRight = new CANTalon(Constants.DriveTrain.FRONT_RIGHT);
27 rearLeft = new CANTalon(Constants.DriveTrain.REAR_LEFT);
28 rearRight = new CANTalon(Constants.DriveTrain.REAR_RIGHT);
29
30 // ENCODERS
31 leftEncoder = new Encoder(Constants.DriveTrain.ENCODER_LEFT_A,
32 Constants.DriveTrain.ENCODER_LEFT_B, false, Encoder.EncodingType.k4X);
33 rightEncoder = new Encoder(Constants.DriveTrain.ENCODER_RIGHT_A,
34 Constants.DriveTrain.ENCODER_RIGHT_B, false, Encoder.EncodingType.k4X);
35
36 leftEncoder.setDistancePerPulse(INCHES_PER_PULSE);
37 rightEncoder.setDistancePerPulse(INCHES_PER_PULSE);
38
39 // ROBOT DRIVE
40 robotDrive = new RobotDrive(frontLeft, rearLeft, frontRight, rearRight);
41 }
42
43 public static DriveTrain getDriveTrain() {
44 if (driveTrain == null) {
45 driveTrain = new DriveTrain();
46 }
47 return driveTrain;
48 }
49
50 // DRIVE METHODS
51 public void setMotorValues(final double left, final double right) {
52 frontLeft.set(left);
53 rearLeft.set(left);
54
55 frontRight.set(-right);
56 rearRight.set(-right);
57 }
58
59 public void joystickDrive(final double thrust, final double twist) {
60 robotDrive.arcadeDrive(thrust, twist, true);
61 }
62
63 public void stop() {
64 setMotorValues(0, 0);
65 }
66
67 public double getFrontLeftMotorVal() {
68 return frontLeft.get();
69 }
70
71 public double getFrontRightMotorVal() {
72 return frontRight.get();
73 }
74
75 public double getRearLeftMotorVal() {
76 return frontLeft.get();
77 }
78
79 public double getRearRightMotorVal() {
80 return frontLeft.get();
81 }
82
83 // ENCODER METHODS
84
85 public double getLeftEncoderDistance() {
86 return leftEncoder.getDistance();
87 }
88
89 public double getRightEncoderDistance() {
90 return rightEncoder.getDistance();
91 }
92
93 public double getAvgEncoderDistance() {
94 return (leftEncoder.getDistance() + rightEncoder.getDistance()) / 2;
95 }
96
97 public void resetEncoders() {
98 leftEncoder.reset();
99 rightEncoder.reset();
100 }
101
102 public double getLeftSpeed() {
103 return leftEncoder.getRate();
104 }
105
106 public double getRightSpeed() {
107 return rightEncoder.getRate();
108 }
109
110 public double getSpeed() {
111 return (getLeftSpeed() + getRightSpeed()) / 2.0;
112 }
113
114 @Override
115 protected void initDefaultCommand() {
116 setDefaultCommand(new JoystickDrive());
117 }
118
119 }