1 package org
.usfirst
.frc
.team3501
.robot
.subsystems
;
3 import org
.usfirst
.frc
.team3501
.robot
.Constants
;
4 import org
.usfirst
.frc
.team3501
.robot
.Lidar
;
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
;
12 public class DriveTrain
extends Subsystem
{
13 // Drivetrain related objects
14 private Encoder leftEncoder
, rightEncoder
;
15 public static Lidar lidar
;
16 private CANTalon frontLeft
, frontRight
, rearLeft
, rearRight
;
19 frontLeft
= new CANTalon(Constants
.DriveTrain
.FRONT_LEFT
);
20 frontRight
= new CANTalon(Constants
.DriveTrain
.FRONT_RIGHT
);
21 rearLeft
= new CANTalon(Constants
.DriveTrain
.REAR_LEFT
);
22 rearRight
= new CANTalon(Constants
.DriveTrain
.REAR_RIGHT
);
24 lidar
= new Lidar(I2C
.Port
.kOnboard
);
25 leftEncoder
= new Encoder(Constants
.DriveTrain
.ENCODER_LEFT_A
,
26 Constants
.DriveTrain
.ENCODER_LEFT_B
, false, EncodingType
.k4X
);
27 rightEncoder
= new Encoder(Constants
.DriveTrain
.ENCODER_RIGHT_A
,
28 Constants
.DriveTrain
.ENCODER_RIGHT_B
, false, EncodingType
.k4X
);
29 leftEncoder
.setDistancePerPulse(Constants
.DriveTrain
.INCHES_PER_PULSE
);
30 rightEncoder
.setDistancePerPulse(Constants
.DriveTrain
.INCHES_PER_PULSE
);
34 protected void initDefaultCommand() {
37 public void resetEncoders() {
42 public double getLidarDistance() {
43 return lidar
.pidGet();
46 public double getRightSpeed() {
47 return rightEncoder
.getRate(); // in inches per second
50 public double getLeftSpeed() {
51 return leftEncoder
.getRate(); // in inches per second
54 public double getSpeed() {
55 return (getLeftSpeed() + getRightSpeed()) / 2.0; // in inches per second
58 public double getRightDistance() {
59 return rightEncoder
.getDistance(); // in inches
62 public double getLeftDistance() {
63 return leftEncoder
.getDistance(); // in inches
66 public double getDistance() {
67 return (getRightDistance() + getLeftDistance()) / 2.0; // in inches
74 public void setMotorSpeeds(double leftSpeed
, double rightSpeed
) {
75 // speed passed to right motor is negative because right motor rotates in
77 this.frontLeft
.set(leftSpeed
);
78 this.frontRight
.set(-rightSpeed
);
79 this.rearLeft
.set(leftSpeed
);
80 this.rearRight
.set(-rightSpeed
);