|
7 | 7 |
|
8 | 8 | package org.usfirst.frc.team199.Robot2018; |
9 | 9 |
|
10 | | - |
11 | | -import edu.wpi.first.wpilibj.SpeedController; |
| 10 | +import org.usfirst.frc.team199.Robot2018.autonomous.PIDSourceAverage; |
| 11 | +import org.usfirst.frc.team199.Robot2018.autonomous.VelocityPIDController; |
12 | 12 |
|
13 | 13 | import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX; |
14 | 14 | import com.ctre.phoenix.motorcontrol.can.WPI_VictorSPX; |
15 | 15 | import com.kauailabs.navx.frc.AHRS; |
16 | 16 |
|
17 | | -import edu.wpi.first.wpilibj.AnalogGyro; |
| 17 | +import edu.wpi.first.wpilibj.DigitalInput; |
| 18 | +import edu.wpi.first.wpilibj.DigitalSource; |
18 | 19 | import edu.wpi.first.wpilibj.DoubleSolenoid; |
19 | 20 | import edu.wpi.first.wpilibj.Encoder; |
20 | | -import edu.wpi.first.wpilibj.PIDController; |
| 21 | +import edu.wpi.first.wpilibj.PIDSourceType; |
21 | 22 | import edu.wpi.first.wpilibj.SerialPort; |
22 | 23 | import edu.wpi.first.wpilibj.SpeedControllerGroup; |
23 | 24 | import edu.wpi.first.wpilibj.drive.DifferentialDrive; |
24 | 25 | import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; |
25 | 26 |
|
26 | | - |
27 | 27 | /** |
28 | 28 | * The RobotMap is a mapping from the ports sensors and actuators are wired into |
29 | 29 | * to a variable name. This provides flexibility changing wiring, makes checking |
30 | 30 | * the wiring easier and significantly reduces the number of magic numbers |
31 | 31 | * floating around. |
32 | 32 | */ |
33 | 33 | public class RobotMap { |
34 | | - // For example to map the left and right motors, you could define the |
35 | | - // following variables to use with your drivetrain subsystem. |
36 | | - // public static int leftMotor = 1; |
37 | | - // public static int rightMotor = 2; |
38 | | - |
39 | | - // If you are using multiple modules, make sure to define both the port |
40 | | - // number and the module. For example you with a rangefinder: |
41 | | - // public static int rangefinderPort = 1; |
42 | | - // public static int rangefinderModule = 1; |
43 | | - |
| 34 | + |
44 | 35 | public static WPI_TalonSRX intakeMotor; |
45 | 36 | public static WPI_TalonSRX liftMotor; |
46 | 37 | public static WPI_TalonSRX climberMotor; |
47 | | - |
48 | | - public static Encoder leftEnc; |
49 | | - public static WPI_TalonSRX dtLeftDrive; |
| 38 | + |
| 39 | + public static DigitalSource leftEncPort1; |
| 40 | + public static DigitalSource leftEncPort2; |
| 41 | + public static Encoder leftEncDist; |
| 42 | + public static Encoder leftEncRate; |
| 43 | + public static WPI_TalonSRX dtLeftMaster; |
50 | 44 | public static WPI_VictorSPX dtLeftSlave; |
51 | 45 | public static SpeedControllerGroup dtLeft; |
| 46 | + public static VelocityPIDController leftVelocityController; |
52 | 47 |
|
53 | | - public static Encoder rightEnc; |
54 | | - public static WPI_TalonSRX dtRightDrive; |
| 48 | + public static DigitalSource rightEncPort1; |
| 49 | + public static DigitalSource rightEncPort2; |
| 50 | + public static Encoder rightEncDist; |
| 51 | + public static Encoder rightEncRate; |
| 52 | + public static WPI_TalonSRX dtRightMaster; |
55 | 53 | public static WPI_VictorSPX dtRightSlave; |
56 | 54 | public static SpeedControllerGroup dtRight; |
| 55 | + public static VelocityPIDController rightVelocityController; |
| 56 | + |
57 | 57 | public static DifferentialDrive robotDrive; |
58 | | - public static PIDController turnController; |
59 | | - // public static PIDController moveController; |
60 | | - public static PIDController moveLeftController; |
61 | | - public static PIDController moveRightController; |
| 58 | + public static PIDSourceAverage distEncAvg; |
62 | 59 |
|
63 | | - public static AHRS ahrs; |
64 | | - public static AnalogGyro dtGyro; |
| 60 | + public static AHRS fancyGyro; |
65 | 61 | public static DoubleSolenoid dtGear; |
66 | 62 |
|
67 | 63 | /** |
@@ -95,69 +91,61 @@ private void configSPX(WPI_VictorSPX mc) { |
95 | 91 | } |
96 | 92 |
|
97 | 93 | public RobotMap() { |
98 | | - |
| 94 | + |
99 | 95 | intakeMotor = new WPI_TalonSRX(getPort("IntakeTalonSRX", 4)); |
100 | 96 | configSRX(intakeMotor); |
101 | 97 | liftMotor = new WPI_TalonSRX(getPort("LiftTalonSRX", 5)); |
102 | 98 | configSRX(liftMotor); |
103 | 99 | climberMotor = new WPI_TalonSRX(getPort("ClimberTalonSRX", 6)); |
104 | 100 | configSRX(climberMotor); |
105 | 101 |
|
106 | | - leftEnc = new Encoder(getPort("1LeftEnc", 0), getPort("2LeftEnc", 1)); |
107 | | - dtLeftDrive = new WPI_TalonSRX(getPort("LeftTalonSRXDrive", 0)); |
108 | | - configSRX(dtLeftDrive); |
| 102 | + leftEncPort1 = new DigitalInput(getPort("1LeftEnc", 0)); |
| 103 | + leftEncPort2 = new DigitalInput(getPort("2LeftEnc", 1)); |
| 104 | + leftEncDist = new Encoder(leftEncPort1, leftEncPort2); |
| 105 | + leftEncDist.setPIDSourceType(PIDSourceType.kDisplacement); |
| 106 | + leftEncRate = new Encoder(leftEncPort1, leftEncPort2); |
| 107 | + leftEncRate.setPIDSourceType(PIDSourceType.kRate); |
| 108 | + dtLeftMaster = new WPI_TalonSRX(getPort("LeftTalonSRXMaster", 0)); |
| 109 | + configSRX(dtLeftMaster); |
109 | 110 | dtLeftSlave = new WPI_VictorSPX(getPort("LeftTalonSPXSlave", 1)); |
110 | 111 | configSPX(dtLeftSlave); |
111 | | - dtLeft = new SpeedControllerGroup(dtLeftDrive, dtLeftSlave); |
112 | | - |
113 | | - rightEnc = new Encoder(getPort("1RightEnc", 2), getPort("2RightEnc", 3)); |
114 | | - dtRightDrive = new WPI_TalonSRX(getPort("RightTalonSRXDrive", 2)); |
115 | | - configSRX(dtRightDrive); |
| 112 | + dtLeft = new SpeedControllerGroup(dtLeftMaster, dtLeftSlave); |
| 113 | + |
| 114 | + leftVelocityController = new VelocityPIDController(Robot.getConst("MoveLeftkP", 1), |
| 115 | + Robot.getConst("MoveLeftkI", 0), Robot.getConst("MoveLeftkD", 0), 1 / Robot.getConst("MaxSpeed", 17), |
| 116 | + leftEncRate, dtLeft); |
| 117 | + leftVelocityController.enable(); |
| 118 | + leftVelocityController.setInputRange(0, Double.MAX_VALUE); |
| 119 | + leftVelocityController.setOutputRange(-1.0, 1.0); |
| 120 | + leftVelocityController.setContinuous(false); |
| 121 | + leftVelocityController.setAbsoluteTolerance(Robot.getConst("MoveToleranceLeft", 2)); |
| 122 | + |
| 123 | + rightEncPort1 = new DigitalInput(getPort("1RightEnc", 2)); |
| 124 | + rightEncPort2 = new DigitalInput(getPort("2RightEnc", 3)); |
| 125 | + rightEncDist = new Encoder(leftEncPort1, leftEncPort2); |
| 126 | + rightEncDist.setPIDSourceType(PIDSourceType.kDisplacement); |
| 127 | + rightEncRate = new Encoder(leftEncPort1, leftEncPort2); |
| 128 | + rightEncRate.setPIDSourceType(PIDSourceType.kRate); |
| 129 | + dtRightMaster = new WPI_TalonSRX(getPort("RightTalonSRXMaster", 2)); |
| 130 | + configSRX(dtRightMaster); |
116 | 131 | dtRightSlave = new WPI_VictorSPX(getPort("RightTalonSPXSlave", 3)); |
117 | 132 | configSPX(dtRightSlave); |
118 | | - dtRight = new SpeedControllerGroup(dtRightDrive, dtRightSlave); |
119 | | - |
120 | | - robotDrive = new DifferentialDrive(dtLeft, dtRight); |
121 | | - |
122 | | - // moveController = new PIDController(Robot.getConst("MovekP", 1), |
123 | | - // Robot.getConst("MovekI", 0), |
124 | | - // Robot.getConst("MovekD", 0), Robot.dt, Robot.dt); |
125 | | - // moveController.disable(); |
126 | | - // moveController.setInputRange(0, Double.MAX_VALUE); |
127 | | - // moveController.setOutputRange(-1.0, 1.0); |
128 | | - // moveController.setContinuous(false); |
129 | | - // moveController.setAbsoluteTolerance(Robot.getConst("MoveTolerance", 2)); |
130 | | - |
131 | | - |
132 | | - ahrs = new AHRS(SerialPort.Port.kMXP); |
133 | | - dtGyro = new AnalogGyro(getPort("Gyro", 0)); |
134 | | - dtGear = new DoubleSolenoid(getPort("1dtGearSolenoid", 0), getPort("2dtGearSolenoid", 1)); |
| 133 | + dtRight = new SpeedControllerGroup(dtRightMaster, dtRightSlave); |
135 | 134 |
|
136 | | - } |
137 | | - |
138 | | - public void initPIDControllers() { |
139 | | - turnController = new PIDController(Robot.getConst("TurnkP", 1), Robot.getConst("TurnkI", 0), |
140 | | - Robot.getConst("TurnkD", 0), ahrs, Robot.dt); |
141 | | - turnController.disable(); |
142 | | - turnController.setInputRange(-180, 180); |
143 | | - turnController.setOutputRange(-1.0, 1.0); |
144 | | - turnController.setContinuous(); |
145 | | - turnController.setAbsoluteTolerance(Robot.getConst("TurnTolerance", 1)); |
146 | | - |
147 | | - moveLeftController = new PIDController(Robot.getConst("MoveLeftkP", 1), Robot.getConst("MoveLeftkI", 0), |
148 | | - Robot.getConst("MoveLeftkD", 0), Robot.ld, Robot.ld); |
149 | | - moveLeftController.disable(); |
150 | | - moveLeftController.setInputRange(0, Double.MAX_VALUE); |
151 | | - moveLeftController.setOutputRange(-1.0, 1.0); |
152 | | - moveLeftController.setContinuous(false); |
153 | | - moveLeftController.setAbsoluteTolerance(Robot.getConst("ConstMoveToleranceLeft", 2)); |
154 | | - moveRightController = new PIDController(Robot.getConst("ConstMoveRightkP", 1), |
155 | | - Robot.getConst("ConstMoveRightkI", 0), Robot.getConst("ConstMoveRightkD", 0), Robot.rd, Robot.rd); |
156 | | - moveRightController.disable(); |
157 | | - moveRightController.setInputRange(0, Double.MAX_VALUE); |
158 | | - moveRightController.setOutputRange(-1.0, 1.0); |
159 | | - moveRightController.setContinuous(false); |
160 | | - moveRightController.setAbsoluteTolerance(Robot.getConst("ConstMoveToleranceRight", 2)); |
| 135 | + rightVelocityController = new VelocityPIDController(Robot.getConst("MoveRightkP", 1), |
| 136 | + Robot.getConst("MoveRightkI", 0), Robot.getConst("MoveRightkD", 0), 1 / Robot.getConst("MaxSpeed", 17), |
| 137 | + rightEncRate, dtRight); |
| 138 | + rightVelocityController.enable(); |
| 139 | + rightVelocityController.setInputRange(0, Double.MAX_VALUE); |
| 140 | + rightVelocityController.setOutputRange(-1.0, 1.0); |
| 141 | + rightVelocityController.setContinuous(false); |
| 142 | + rightVelocityController.setAbsoluteTolerance(Robot.getConst("MoveToleranceRight", 2)); |
| 143 | + |
| 144 | + robotDrive = new DifferentialDrive(leftVelocityController, rightVelocityController); |
| 145 | + |
| 146 | + distEncAvg = new PIDSourceAverage(leftEncDist, rightEncDist); |
| 147 | + fancyGyro = new AHRS(SerialPort.Port.kMXP); |
| 148 | + dtGear = new DoubleSolenoid(getPort("1dtGearSolenoid", 0), getPort("2dtGearSolenoid", 1)); |
161 | 149 | } |
162 | 150 |
|
163 | 151 | /** |
|
0 commit comments