Skip to content
This repository was archived by the owner on Sep 14, 2019. It is now read-only.

Commit 52a5c61

Browse files
authored
Merge pull request #41 from lhmcgann/master
PID, Drivetrain, cleanup, other little things
2 parents 089009a + 9753c57 commit 52a5c61

27 files changed

Lines changed: 583 additions & 949 deletions

.gitignore

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -2,5 +2,3 @@ bin/
22
build/
33
dist/
44
.DS_Store
5-
*auto*
6-
*Auto*

Robot2018/src/org/usfirst/frc/team199/Robot2018/OI.java

Lines changed: 21 additions & 48 deletions
Original file line numberDiff line numberDiff line change
@@ -24,43 +24,16 @@
2424
* interface to the commands and command groups that allow control of the robot.
2525
*/
2626
public class OI {
27-
//// CREATING BUTTONS
28-
// One type of button is a joystick button which is any button on a
29-
//// joystick.
30-
// You create one by telling it which joystick it's on and which button
31-
// number it is.
32-
// Joystick stick = new Joystick(port);
33-
// Button button = new JoystickButton(stick, buttonNumber);
34-
35-
// There are a few additional built in buttons you can use. Additionally,
36-
// by subclassing Button you can create custom triggers and bind those to
37-
// commands the same as any other Button.
38-
39-
//// TRIGGERING COMMANDS WITH BUTTONS
40-
// Once you have a button, it's trivial to bind it to a button in one of
41-
// three ways:
42-
43-
// Start the command when the button is pressed and let it run the command
44-
// until it is finished as determined by it's isFinished method.
45-
// button.whenPressed(new ExampleCommand());
46-
47-
// Run the command while the button is being held down and interrupt it once
48-
// the button is released.
49-
// button.whileHeld(new ExampleCommand());
50-
51-
// Start the command when the button is released and let it run the command
52-
// until it is finished as determined by it's isFinished method.
53-
// button.whenReleased(new ExampleCommand());
5427

5528
public Joystick leftJoy;
56-
private JoystickButton shiftLowGear;
57-
private JoystickButton shiftHighGear;
58-
private JoystickButton shiftDriveType;
59-
private JoystickButton PIDMove;
60-
private JoystickButton PIDTurn;
29+
private JoystickButton shiftLowGearButton;
30+
private JoystickButton shiftHighGearButton;
31+
private JoystickButton shiftDriveTypeButton;
32+
private JoystickButton PIDMoveButton;
33+
private JoystickButton PIDTurnButton;
6134
public Joystick rightJoy;
62-
private JoystickButton updatePidConstants;
63-
private JoystickButton updateEncoderDPP;
35+
private JoystickButton updatePIDConstantsButton;
36+
private JoystickButton updateEncoderDPPButton;
6437
public Joystick manipulator;
6538

6639
public int getButton(String key, int def) {
@@ -72,22 +45,22 @@ public int getButton(String key, int def) {
7245

7346
public OI() {
7447
leftJoy = new Joystick(0);
75-
shiftLowGear = new JoystickButton(leftJoy, getButton("Shift Low Gear", 3));
76-
shiftLowGear.whenPressed(new ShiftLowGear());
77-
shiftHighGear = new JoystickButton(leftJoy, getButton("Shift High Gear", 5));
78-
shiftHighGear.whenPressed(new ShiftHighGear());
79-
shiftDriveType = new JoystickButton(leftJoy, getButton("Shift Drive Type", 2));
80-
shiftDriveType.whenPressed(new ShiftDriveType());
81-
PIDMove = new JoystickButton(leftJoy, getButton("PID Move", 7));
82-
PIDMove.whenPressed(new PIDMove(40, Robot.dt));
83-
PIDTurn = new JoystickButton(leftJoy, getButton("PID Turn", 8));
84-
PIDTurn.whenPressed(new PIDTurn(30, Robot.dt));
48+
shiftLowGearButton = new JoystickButton(leftJoy, getButton("Shift Low Gear", 3));
49+
shiftLowGearButton.whenPressed(new ShiftLowGear());
50+
shiftHighGearButton = new JoystickButton(leftJoy, getButton("Shift High Gear", 5));
51+
shiftHighGearButton.whenPressed(new ShiftHighGear());
52+
shiftDriveTypeButton = new JoystickButton(leftJoy, getButton("Shift Drive Type", 2));
53+
shiftDriveTypeButton.whenPressed(new ShiftDriveType());
54+
PIDMoveButton = new JoystickButton(leftJoy, getButton("PID Move", 7));
55+
PIDMoveButton.whenPressed(new PIDMove(40, Robot.dt, RobotMap.distEncAvg));
56+
PIDTurnButton = new JoystickButton(leftJoy, getButton("PID Turn", 8));
57+
PIDTurnButton.whenPressed(new PIDTurn(30, Robot.dt, RobotMap.fancyGyro));
8558

8659
rightJoy = new Joystick(1);
87-
updatePidConstants = new JoystickButton(rightJoy, getButton("Get PID Constants", 8));
88-
updatePidConstants.whenPressed(new UpdatePIDConstants());
89-
updateEncoderDPP = new JoystickButton(rightJoy, getButton("Get Encoder Dist Per Pulse", 9));
90-
updateEncoderDPP.whenPressed(new SetDistancePerPulse());
60+
updatePIDConstantsButton = new JoystickButton(rightJoy, getButton("Get PID Constants", 8));
61+
updatePIDConstantsButton.whenPressed(new UpdatePIDConstants());
62+
updateEncoderDPPButton = new JoystickButton(rightJoy, getButton("Get Encoder Dist Per Pulse", 9));
63+
updateEncoderDPPButton.whenPressed(new SetDistancePerPulse());
9164

9265
manipulator = new Joystick(2);
9366
}

Robot2018/src/org/usfirst/frc/team199/Robot2018/Robot.java

Lines changed: 0 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -13,9 +13,7 @@
1313
import org.usfirst.frc.team199.Robot2018.subsystems.ClimberAssist;
1414
import org.usfirst.frc.team199.Robot2018.subsystems.Drivetrain;
1515
import org.usfirst.frc.team199.Robot2018.subsystems.IntakeEject;
16-
import org.usfirst.frc.team199.Robot2018.subsystems.LeftDrive;
1716
import org.usfirst.frc.team199.Robot2018.subsystems.Lift;
18-
import org.usfirst.frc.team199.Robot2018.subsystems.RightDrive;
1917

2018
import edu.wpi.first.wpilibj.DriverStation;
2119
import edu.wpi.first.wpilibj.Preferences;
@@ -40,8 +38,6 @@ public class Robot extends TimedRobot {
4038
public static Lift lift;
4139
public static RobotMap rmap;
4240
public static Drivetrain dt;
43-
public static LeftDrive ld;
44-
public static RightDrive rd;
4541
public static Listener listen;
4642

4743
public static OI oi;
@@ -79,9 +75,6 @@ public void robotInit() {
7975
intakeEject = new IntakeEject();
8076
lift = new Lift();
8177
dt = new Drivetrain();
82-
rmap.initPIDControllers();
83-
ld = new LeftDrive();
84-
rd = new RightDrive();
8578
oi = new OI();
8679

8780
// auto position chooser

Robot2018/src/org/usfirst/frc/team199/Robot2018/RobotMap.java

Lines changed: 65 additions & 77 deletions
Original file line numberDiff line numberDiff line change
@@ -7,61 +7,57 @@
77

88
package org.usfirst.frc.team199.Robot2018;
99

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;
1212

1313
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
1414
import com.ctre.phoenix.motorcontrol.can.WPI_VictorSPX;
1515
import com.kauailabs.navx.frc.AHRS;
1616

17-
import edu.wpi.first.wpilibj.AnalogGyro;
17+
import edu.wpi.first.wpilibj.DigitalInput;
18+
import edu.wpi.first.wpilibj.DigitalSource;
1819
import edu.wpi.first.wpilibj.DoubleSolenoid;
1920
import edu.wpi.first.wpilibj.Encoder;
20-
import edu.wpi.first.wpilibj.PIDController;
21+
import edu.wpi.first.wpilibj.PIDSourceType;
2122
import edu.wpi.first.wpilibj.SerialPort;
2223
import edu.wpi.first.wpilibj.SpeedControllerGroup;
2324
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
2425
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
2526

26-
2727
/**
2828
* The RobotMap is a mapping from the ports sensors and actuators are wired into
2929
* to a variable name. This provides flexibility changing wiring, makes checking
3030
* the wiring easier and significantly reduces the number of magic numbers
3131
* floating around.
3232
*/
3333
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+
4435
public static WPI_TalonSRX intakeMotor;
4536
public static WPI_TalonSRX liftMotor;
4637
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;
5044
public static WPI_VictorSPX dtLeftSlave;
5145
public static SpeedControllerGroup dtLeft;
46+
public static VelocityPIDController leftVelocityController;
5247

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;
5553
public static WPI_VictorSPX dtRightSlave;
5654
public static SpeedControllerGroup dtRight;
55+
public static VelocityPIDController rightVelocityController;
56+
5757
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;
6259

63-
public static AHRS ahrs;
64-
public static AnalogGyro dtGyro;
60+
public static AHRS fancyGyro;
6561
public static DoubleSolenoid dtGear;
6662

6763
/**
@@ -95,69 +91,61 @@ private void configSPX(WPI_VictorSPX mc) {
9591
}
9692

9793
public RobotMap() {
98-
94+
9995
intakeMotor = new WPI_TalonSRX(getPort("IntakeTalonSRX", 4));
10096
configSRX(intakeMotor);
10197
liftMotor = new WPI_TalonSRX(getPort("LiftTalonSRX", 5));
10298
configSRX(liftMotor);
10399
climberMotor = new WPI_TalonSRX(getPort("ClimberTalonSRX", 6));
104100
configSRX(climberMotor);
105101

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);
109110
dtLeftSlave = new WPI_VictorSPX(getPort("LeftTalonSPXSlave", 1));
110111
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);
116131
dtRightSlave = new WPI_VictorSPX(getPort("RightTalonSPXSlave", 3));
117132
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);
135134

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));
161149
}
162150

163151
/**
Lines changed: 37 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,37 @@
1+
package org.usfirst.frc.team199.Robot2018.autonomous;
2+
3+
import edu.wpi.first.wpilibj.PIDSource;
4+
import edu.wpi.first.wpilibj.PIDSourceType;
5+
6+
public class PIDSourceAverage implements PIDSource {
7+
8+
private PIDSource lSrc;
9+
private PIDSource rSrc;
10+
private PIDSourceType type;
11+
12+
public PIDSourceAverage(PIDSource leftSource, PIDSource rightSource) {
13+
lSrc = leftSource;
14+
rSrc = rightSource;
15+
if (leftSource.getPIDSourceType().equals(rightSource.getPIDSourceType())) {
16+
type = leftSource.getPIDSourceType();
17+
} else {
18+
throw new IllegalArgumentException();
19+
}
20+
}
21+
22+
@Override
23+
public void setPIDSourceType(PIDSourceType pidSource) {
24+
type = pidSource;
25+
}
26+
27+
@Override
28+
public PIDSourceType getPIDSourceType() {
29+
return type;
30+
}
31+
32+
@Override
33+
public double pidGet() {
34+
return (lSrc.pidGet() + rSrc.pidGet()) / 2;
35+
}
36+
37+
}

0 commit comments

Comments
 (0)