4f686879a8194cb59db058f01f124846077f5883
[3501/stronghold-2016] / 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.Lidar;
5
6 import edu.wpi.first.wpilibj.CANTalon;
7 import edu.wpi.first.wpilibj.CounterBase.EncodingType;
8 import edu.wpi.first.wpilibj.Encoder;
9 import edu.wpi.first.wpilibj.I2C;
10 import edu.wpi.first.wpilibj.command.Subsystem;
11
12 public class DriveTrain extends Subsystem {
13 // Drivetrain related objects
14 private Encoder leftEncoder, rightEncoder;
15 public static Lidar leftLidar;
16 public static Lidar rightLidar;
17 private CANTalon frontLeft, frontRight, rearLeft, rearRight;
18
19 public DriveTrain() {
20 frontLeft = new CANTalon(Constants.DriveTrain.FRONT_LEFT);
21 frontRight = new CANTalon(Constants.DriveTrain.FRONT_RIGHT);
22 rearLeft = new CANTalon(Constants.DriveTrain.REAR_LEFT);
23 rearRight = new CANTalon(Constants.DriveTrain.REAR_RIGHT);
24
25 leftLidar = new Lidar(I2C.Port.kOnboard);
26 rightLidar = new Lidar(I2C.Port.kOnboard); // TODO: find port for second
27 // lidar
28 leftEncoder = new Encoder(Constants.DriveTrain.ENCODER_LEFT_A,
29 Constants.DriveTrain.ENCODER_LEFT_B, false, EncodingType.k4X);
30 rightEncoder = new Encoder(Constants.DriveTrain.ENCODER_RIGHT_A,
31 Constants.DriveTrain.ENCODER_RIGHT_B, false, EncodingType.k4X);
32 leftEncoder.setDistancePerPulse(Constants.DriveTrain.INCHES_PER_PULSE);
33 rightEncoder.setDistancePerPulse(Constants.DriveTrain.INCHES_PER_PULSE);
34 }
35
36 @Override
37 protected void initDefaultCommand() {
38 }
39
40 public void resetEncoders() {
41 leftEncoder.reset();
42 rightEncoder.reset();
43 }
44
45 public double getLeftLidarDistance() {
46 return leftLidar.pidGet();
47 }
48
49 public double getsRightLidarDistance() {
50 return rightLidar.pidGet();
51 }
52
53 public double getRightSpeed() {
54 return rightEncoder.getRate(); // in inches per second
55 }
56
57 public double getLeftSpeed() {
58 return leftEncoder.getRate(); // in inches per second
59 }
60
61 public double getSpeed() {
62 return (getLeftSpeed() + getRightSpeed()) / 2.0; // in inches per second
63 }
64
65 public double getRightDistance() {
66 return rightEncoder.getDistance(); // in inches
67 }
68
69 public double getLeftDistance() {
70 return leftEncoder.getDistance(); // in inches
71 }
72
73 public double getDistance() {
74 return (getRightDistance() + getLeftDistance()) / 2.0; // in inches
75 }
76
77 public void stop() {
78 setMotorSpeeds(0, 0);
79 }
80
81 public void setMotorSpeeds(double leftSpeed, double rightSpeed) {
82 // speed passed to right motor is negative because right motor rotates in
83 // opposite direction
84 this.frontLeft.set(leftSpeed);
85 this.frontRight.set(-rightSpeed);
86 this.rearLeft.set(leftSpeed);
87 this.rearRight.set(-rightSpeed);
88 }
89 }