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

Commit 11e0bd4

Browse files
committed
2 parents 7573d5b + 73e6ebc commit 11e0bd4

5 files changed

Lines changed: 145 additions & 44 deletions

File tree

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

Lines changed: 25 additions & 18 deletions
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,9 @@
1+
/*----------------------------------------------------------------------------*/
2+
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
3+
/* Open Source Software - may be modified and shared by FRC teams. The code */
4+
/* must be accompanied by the FIRST BSD license file in the root directory of */
5+
/* the project. */
6+
/*----------------------------------------------------------------------------*/
17

28
package org.usfirst.frc.team199.Robot2018;
39

@@ -41,13 +47,13 @@ public class Robot extends TimedRobot {
4147
public static Listener listen;
4248

4349
public static OI oi;
44-
50+
4551
public static Map<String, ArrayList<String[]>> autoScripts;
4652

4753
Command autonomousCommand;
4854
SendableChooser<Position> posChooser = new SendableChooser<Position>();
4955
Map<String, SendableChooser<Strategy>> stratChoosers = new HashMap<String, SendableChooser<Strategy>>();
50-
String[] fmsPossibilities = {"LL", "LR", "RL", "RR"};
56+
String[] fmsPossibilities = { "LL", "LR", "RL", "RR" };
5157

5258
public static double getConst(String key, double def) {
5359
if (!SmartDashboard.containsKey("Const/" + key)) {
@@ -64,8 +70,8 @@ public static boolean getBool(String key, boolean def) {
6470
}
6571

6672
/**
67-
* This function is run when the robot is first started up and should be used
68-
* for any initialization code.
73+
* This function is run when the robot is first started up and should be
74+
* used for any initialization code.
6975
*/
7076
@Override
7177
public void robotInit() {
@@ -76,13 +82,13 @@ public void robotInit() {
7682
lift = new Lift();
7783
dt = new Drivetrain();
7884
oi = new OI();
79-
85+
8086
// auto position chooser
8187
for (Position p : Position.values()) {
8288
posChooser.addObject(p.getSDName(), p);
8389
}
8490
SmartDashboard.putData("Starting Position", posChooser);
85-
91+
8692
// auto strategy choosers
8793
for (String input : fmsPossibilities) {
8894
SendableChooser<Strategy> chooser = new SendableChooser<Strategy>();
@@ -92,20 +98,21 @@ public void robotInit() {
9298
SmartDashboard.putData(input, chooser);
9399
stratChoosers.put(input, chooser);
94100
}
95-
101+
96102
// auto delay chooser
97103
SmartDashboard.putNumber("Auto Delay", 0);
98-
99-
// parse scripts from Preferences, which maintains values throughout reboots
104+
105+
// parse scripts from Preferences, which maintains values throughout
106+
// reboots
100107
autoScripts = AutoUtils.parseScriptFile(Preferences.getInstance().getString("autoscripts", ""));
101108

102109
listen = new Listener();
103110
}
104111

105112
/**
106-
* This function is called once each time the robot enters Disabled mode. You
107-
* can use it to reset any subsystem information you want to clear when the
108-
* robot is disabled.
113+
* This function is called once each time the robot enters Disabled mode.
114+
* You can use it to reset any subsystem information you want to clear when
115+
* the robot is disabled.
109116
*/
110117
@Override
111118
public void disabledInit() {
@@ -118,7 +125,7 @@ public void disabledPeriodic() {
118125
}
119126

120127
/**
121-
* This function is called once during the start of autonomous in order to
128+
* This function is called once during the start of autonomous in order to
122129
* grab values from SmartDashboard and the FMS and call the Autonomous
123130
* command with those values.
124131
*/
@@ -127,14 +134,14 @@ public void autonomousInit() {
127134
String fmsInput = DriverStation.getInstance().getGameSpecificMessage();
128135
Position startPos = posChooser.getSelected();
129136
double autoDelay = SmartDashboard.getNumber("Auto Delay", 0);
130-
137+
131138
Map<String, Strategy> strategies = new HashMap<String, Strategy>();
132139
for (Map.Entry<String, SendableChooser<Strategy>> entry : stratChoosers.entrySet()) {
133-
String key = entry.getKey();
134-
SendableChooser<Strategy> chooser = entry.getValue();
135-
strategies.put(key, chooser.getSelected());
140+
String key = entry.getKey();
141+
SendableChooser<Strategy> chooser = entry.getValue();
142+
strategies.put(key, chooser.getSelected());
136143
}
137-
144+
138145
Autonomous auto = new Autonomous(startPos, strategies, autoDelay, fmsInput, false);
139146
auto.start();
140147
}

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

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -73,11 +73,20 @@ public class RobotMap {
7373
* the TalonSRX to configure
7474
*/
7575
private void configSRX(WPI_TalonSRX mc) {
76+
// stuff cole said to put
7677
int kTimeout = (int) Robot.getConst("kTimeoutMs", 10);
7778
mc.configNominalOutputForward(0, kTimeout);
7879
mc.configNominalOutputReverse(0, kTimeout);
7980
mc.configPeakOutputForward(1, kTimeout);
8081
mc.configPeakOutputReverse(-1, kTimeout);
82+
83+
// current limiting stuff cole said to put
84+
mc.configPeakCurrentLimit(0, 0);
85+
mc.configPeakCurrentDuration(0, 0);
86+
// 40 amps is the amp limit of a CIM. also, the PDP has 40 amp circuit breakers,
87+
// so if we went above 40, the motors would stop completely.
88+
mc.configContinuousCurrentLimit(40, 0);
89+
mc.enableCurrentLimit(true);
8190
}
8291

8392
/**
@@ -88,6 +97,7 @@ private void configSRX(WPI_TalonSRX mc) {
8897
* the VictorSPX to configure
8998
*/
9099
private void configSPX(WPI_VictorSPX mc) {
100+
// stuff cole said to put
91101
int kTimeout = (int) Robot.getConst("kTimeoutMs", 10);
92102
mc.configNominalOutputForward(0, kTimeout);
93103
mc.configNominalOutputReverse(0, kTimeout);

Robot2018/src/org/usfirst/frc/team199/Robot2018/commands/PIDMove.java

Lines changed: 52 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -9,26 +9,43 @@
99
import edu.wpi.first.wpilibj.command.Command;
1010

1111
/**
12-
*
12+
* Drives the robot a certain target distance using PID. Implements PIDOutput in
13+
* order to keep move PID centralized in this command.
1314
*/
1415
public class PIDMove extends Command implements PIDOutput {
1516

1617
private double target;
1718
private DrivetrainInterface dt;
1819
private PIDController moveController;
1920

21+
/**
22+
* Constructs this command with a new PIDController. Sets all of the
23+
* controller's PID constants based on SD prefs. Sets the controller's PIDSource
24+
* to the encoder average object and sets its PIDOutput to this command which
25+
* implements PIDOutput's pidWrite() method.
26+
*
27+
* @param targ
28+
* the target distance (in inches) to move to
29+
* @param dt
30+
* the Drivetrain (for actual code) or a DrivetrainInterface (for
31+
* testing)
32+
* @param avg
33+
* the PIDSourceAverage of the DT's two Encoders
34+
*/
2035
public PIDMove(double targ, DrivetrainInterface dt, PIDSourceAverage avg) {
2136
// Use requires() here to declare subsystem dependencies
22-
// eg. requires(chassis);
37+
requires(Robot.dt);
2338
target = targ;
2439
this.dt = dt;
25-
requires(Robot.dt);
2640
double kf = 1 / (dt.getCurrentMaxSpeed() * Robot.getConst("Default PID Update Time", 0.05));
2741
moveController = new PIDController(Robot.getConst("MovekP", 1), Robot.getConst("MovekI", 0),
2842
Robot.getConst("MovekD", 0), kf, avg, this);
2943
}
3044

31-
// Called just before this Command runs the first time
45+
/**
46+
* Called just before this Command runs the first time. Resets the distance
47+
* encoders, sets the moveController's settings, and then enables it.
48+
*/
3249
@Override
3350
public void initialize() {
3451
dt.resetDistEncs();
@@ -42,33 +59,57 @@ public void initialize() {
4259
moveController.enable();
4360
}
4461

45-
// Called repeatedly when this Command is scheduled to run
62+
/**
63+
* Called repeatedly when this Command is scheduled to run. This method is empty
64+
* bc the moveController runs on a different thread as soon as it is enabled in
65+
* initialize().
66+
*/
4667
@Override
4768
protected void execute() {
48-
// This method is empty bc the moveController runs on a different thread as soon
49-
// as it is enabled.
5069
}
5170

52-
// Make this return true when this Command no longer needs to run execute()
71+
/**
72+
* Tells this command to terminate when the moveController has reached its
73+
* target.
74+
*
75+
* @return true if the robot has moved the correct distance, false if not
76+
*/
5377
@Override
5478
protected boolean isFinished() {
5579
return moveController.onTarget();
5680
}
5781

58-
// Called once after isFinished returns true
82+
/**
83+
* Called once after isFinished returns true. Disables and frees the
84+
* moveController, essentially turning it "off" and "deleting" the thread it was
85+
* running on.
86+
*/
5987
@Override
6088
protected void end() {
6189
moveController.disable();
6290
moveController.free();
6391
}
6492

65-
// Called when another command which requires one or more of the same
66-
// subsystems is scheduled to run
93+
/**
94+
* Called when another command which requires one or more of the same subsystems
95+
* is scheduled to run. Disables and frees the moveController, essentially
96+
* turning it "off" and "deleting" the thread it was running on.
97+
*/
6798
@Override
6899
protected void interrupted() {
69100
end();
70101
}
71102

103+
/**
104+
* Implementation of PIDOutput's pidWrite method. Sends the moveController's
105+
* output speed to the motors as the drive/forward speed in DifferentialDrive's
106+
* arcadeDrive method.
107+
*
108+
* @param output
109+
* the output drive/forward speed [-1, 1], calculated by the move
110+
* PIDController, to pass in as the drive/forward speed in
111+
* arcadeDrive()
112+
*/
72113
@Override
73114
public void pidWrite(double output) {
74115
dt.arcadeDrive(output, 0);

Robot2018/src/org/usfirst/frc/team199/Robot2018/commands/PIDTurn.java

Lines changed: 55 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -10,20 +10,35 @@
1010
import edu.wpi.first.wpilibj.command.Command;
1111

1212
/**
13-
*
13+
* Turns the robot to a certain target bearing using PID. Implements PIDOutput
14+
* in order to keep turn PID centralized in this command.
1415
*/
1516
public class PIDTurn extends Command implements PIDOutput {
1617

17-
double target;
18-
DrivetrainInterface dt;
18+
private double target;
19+
private DrivetrainInterface dt;
1920
private PIDController turnController;
2021

22+
/**
23+
* Constructs this command with a new PIDController. Sets all of the
24+
* controller's PID constants based on SD prefs. Sets the controller's PIDSource
25+
* to the AHRS (gyro) object and sets its PIDOutput to this command which
26+
* implements PIDOutput's pidWrite() method.
27+
*
28+
* @param targ
29+
* the target bearing (in degrees) to turn to (so negative if turning
30+
* left, positive if turning right)
31+
* @param dt
32+
* the Drivetrain (for actual code) or a DrivetrainInterface (for
33+
* testing)
34+
* @param ahrs
35+
* the AHRS (gyro)
36+
*/
2137
public PIDTurn(double targ, DrivetrainInterface dt, AHRS ahrs) {
2238
// Use requires() here to declare subsystem dependencies
23-
// eg. requires(chassis);
39+
requires(Robot.dt);
2440
target = targ;
2541
this.dt = dt;
26-
requires(Robot.dt);
2742
// calculates the maximum turning speed in degrees/sec based on the max linear
2843
// speed in inches/s and the distance (inches) between sides of the DT
2944
double maxTurnSpeed = dt.getCurrentMaxSpeed() * 360
@@ -33,7 +48,10 @@ public PIDTurn(double targ, DrivetrainInterface dt, AHRS ahrs) {
3348
Robot.getConst("TurnkD", 0), kf, ahrs, this);
3449
}
3550

36-
// Called just before this Command runs the first time
51+
/**
52+
* Called just before this Command runs the first time. Resets the gyro, sets
53+
* the turnController's settings, and then enables it.
54+
*/
3755
@Override
3856
protected void initialize() {
3957
dt.resetAHRS();
@@ -48,33 +66,57 @@ protected void initialize() {
4866
turnController.enable();
4967
}
5068

51-
// Called repeatedly when this Command is scheduled to run
69+
/**
70+
* Called repeatedly when this Command is scheduled to run. This method is empty
71+
* bc the turnController runs on a different thread as soon as it is enabled in
72+
* initialize().
73+
*/
5274
@Override
5375
protected void execute() {
54-
// This method is empty bc the moveController runs on a different thread as soon
55-
// as it is enabled.
5676
}
5777

58-
// Make this return true when this Command no longer needs to run execute()
78+
/**
79+
* Tells this command to terminate when the turnController has reached its
80+
* target.
81+
*
82+
* @return true if the robot has turned to the correct target bearing, false if
83+
* not
84+
*/
5985
@Override
6086
protected boolean isFinished() {
6187
return turnController.onTarget();
6288
}
6389

64-
// Called once after isFinished returns true
90+
/**
91+
* Called once after isFinished returns true. Disables and frees the
92+
* turnController, essentially turning it "off" and "deleting" the thread it was
93+
* running on.
94+
*/
6595
@Override
6696
protected void end() {
6797
turnController.disable();
6898
turnController.free();
6999
}
70100

71-
// Called when another command which requires one or more of the same
72-
// subsystems is scheduled to run
101+
/**
102+
* Called when another command which requires one or more of the same subsystems
103+
* is scheduled to run. Disables and frees the turnController, essentially
104+
* turning it "off" and "deleting" the thread it was running on.
105+
*/
73106
@Override
74107
protected void interrupted() {
75108
end();
76109
}
77110

111+
/**
112+
* Implementation of PIDOutput's pidWrite method. Sends the turnController's
113+
* output speed to the motors as the turn speed in DifferentialDrive's
114+
* arcadeDrive method.
115+
*
116+
* @param output
117+
* the output turn speed [-1, 1], calculated by the turn
118+
* PIDController, to pass in as the turn speed in arcadeDrive()
119+
*/
78120
@Override
79121
public void pidWrite(double output) {
80122
dt.arcadeDrive(0, output);

Robot2018/test/org/usfirst/frc/team199/Robot2018/ParseScriptFileTest.java

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -108,9 +108,10 @@ void test8() {
108108
@Test
109109
void test9() {
110110
String input = "RRxx:\n"
111-
+ "moveto (42,56) 45\n"
111+
+ "moveto (42,56) 45 # Trailing comment should not break anything \n"
112112
+ "scale\n"
113-
+ "move 46\n"
113+
+ "#move 10\n" // For testing that commented lines are ignored
114+
+ "move 46\n"
114115
+ "LRxx:\n"
115116
+ "intake\n"
116117
+ "turn (32,5)\n";

0 commit comments

Comments
 (0)