1 package org
.usfirst
.frc
.team3501
.robot
.subsystems
;
3 import org
.usfirst
.frc
.team3501
.robot
.Constants
;
4 import org
.usfirst
.frc
.team3501
.robot
.commands
.driving
.JoystickDrive
;
6 import com
.ctre
.CANTalon
;
8 import edu
.wpi
.first
.wpilibj
.ADXRS450_Gyro
;
9 import edu
.wpi
.first
.wpilibj
.DoubleSolenoid
;
10 import edu
.wpi
.first
.wpilibj
.Encoder
;
11 import edu
.wpi
.first
.wpilibj
.RobotDrive
;
12 import edu
.wpi
.first
.wpilibj
.command
.Subsystem
;
14 public class DriveTrain
extends Subsystem
{
15 public static double driveP
= 0.006, driveI
= 0.001, driveD
= -0.002;
16 public static double defaultGyroP
= 0.004, defaultGyroI
= 0.0013,
17 defaultGyroD
= -0.005;
18 private double gyroZero
= 0;
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
;
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 private final DoubleSolenoid shifter
;
31 private ADXRS450_Gyro imu
;
33 private DriveTrain() {
35 frontLeft
= new CANTalon(Constants
.DriveTrain
.FRONT_LEFT
);
36 frontRight
= new CANTalon(Constants
.DriveTrain
.FRONT_RIGHT
);
37 rearLeft
= new CANTalon(Constants
.DriveTrain
.REAR_LEFT
);
38 rearRight
= new CANTalon(Constants
.DriveTrain
.REAR_RIGHT
);
41 leftEncoder
= new Encoder(Constants
.DriveTrain
.ENCODER_LEFT_A
,
42 Constants
.DriveTrain
.ENCODER_LEFT_B
, false, Encoder
.EncodingType
.k4X
);
43 rightEncoder
= new Encoder(Constants
.DriveTrain
.ENCODER_RIGHT_A
,
44 Constants
.DriveTrain
.ENCODER_RIGHT_B
, false, Encoder
.EncodingType
.k4X
);
46 leftEncoder
.setDistancePerPulse(INCHES_PER_PULSE
);
47 rightEncoder
.setDistancePerPulse(INCHES_PER_PULSE
);
50 robotDrive
= new RobotDrive(frontLeft
, rearLeft
, frontRight
, rearRight
);
52 this.imu
= new ADXRS450_Gyro(Constants
.DriveTrain
.GYRO_PORT
);
53 shifter
= DoubleSolenoid(10, Constants
.DriveTrain
.SHIFTER_FORWARD
,
54 Constants
.DriveTrain
.SHIFTER_REVERSE
);
57 public static DriveTrain
getDriveTrain() {
58 if (driveTrain
== null) {
59 driveTrain
= new DriveTrain();
65 public void setMotorValues(final double left
, final double right
) {
69 frontRight
.set(-right
);
70 rearRight
.set(-right
);
73 public void joystickDrive(final double thrust
, final double twist
) {
74 robotDrive
.arcadeDrive(thrust
, twist
, true);
81 public double getLeftMotorVal() {
82 return (frontLeft
.get() + rearLeft
.get()) / 2;
85 public double getRightMotorVal() {
86 return (frontRight
.get() + rearRight
.get()) / 2;
91 public double getLeftEncoderDistance() {
92 return leftEncoder
.getDistance();
95 public double getRightEncoderDistance() {
96 return rightEncoder
.getDistance();
99 public void printEncoderOutput() {
100 // System.out.println("left: " + getLeftEncoderDistance());
101 // System.out.println("right: " + getRightEncoderDistance());
102 System
.out
.println(getAvgEncoderDistance());
105 public double getAvgEncoderDistance() {
106 return (leftEncoder
.getDistance() + rightEncoder
.getDistance()) / 2;
109 public void resetEncoders() {
111 rightEncoder
.reset();
114 public double getLeftSpeed() {
115 return leftEncoder
.getRate();
118 public double getRightSpeed() {
119 return rightEncoder
.getRate();
122 public double getSpeed() {
123 return (getLeftSpeed() + getRightSpeed()) / 2.0;
126 // ------Gyro------//
127 public double getAngle() {
128 return this.imu
.getAngle() - this.gyroZero
;
131 public void resetGyro() {
135 public double getZeroAngle() {
136 return this.gyroZero
;
140 protected void initDefaultCommand() {
141 setDefaultCommand(new JoystickDrive());