Skip to content

Commit 03e3abb

Browse files
author
Noah Gleason
authored
Merge pull request #99 from blair-robot-project/int_hotfix
Int hotfix
2 parents ef62a73 + cbbe56f commit 03e3abb

File tree

283 files changed

+690
-602
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

283 files changed

+690
-602
lines changed

.gitignore

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -37,6 +37,7 @@ robot2017.iws
3737
#Other
3838
.metadata/
3939
.DS_Store
40+
bash.exe.stackdump
4041

4142
#Copied log files
4243
logs/

RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiInterface/drive/UnidirectionalNavXDefaultDrive.java

Lines changed: 8 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -76,9 +76,9 @@ public UnidirectionalNavXDefaultDrive(@JsonProperty(required = true) double abso
7676
double deadband,
7777
@Nullable Double maxAngularVelToEnterLoop,
7878
boolean inverted,
79-
int kP,
80-
int kI,
81-
int kD,
79+
double kP,
80+
double kI,
81+
double kD,
8282
@NotNull @JsonProperty(required = true) BufferTimer driveStraightLoopEntryTimer,
8383
@NotNull @JsonProperty(required = true) T subsystem,
8484
@NotNull @JsonProperty(required = true) OIUnidirectional oi) {
@@ -177,6 +177,11 @@ protected void usePIDOutput(double output) {
177177
//Process the output (minimumOutput, deadband, etc.)
178178
output = processPIDOutput(output);
179179

180+
//Deadband if we're stationary
181+
if(oi.getLeftOutput() == 0 || oi.getRightOutput() == 0){
182+
output=deadbandOutput(output);
183+
}
184+
180185
//Adjust the heading according to the PID output, it'll be positive if we want to go right.
181186
subsystem.setOutput(oi.getLeftOutput() - output, oi.getRightOutput() + output);
182187
}

RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiInterface/drive/UnidirectionalNavXShiftingDefaultDrive.java

Lines changed: 23 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,7 @@
66
import org.usfirst.frc.team449.robot.components.AutoshiftComponent;
77
import org.usfirst.frc.team449.robot.drive.shifting.DriveShiftable;
88
import org.usfirst.frc.team449.robot.drive.unidirectional.DriveUnidirectional;
9+
import org.usfirst.frc.team449.robot.generalInterfaces.shiftable.Shiftable;
910
import org.usfirst.frc.team449.robot.jacksonWrappers.YamlSubsystem;
1011
import org.usfirst.frc.team449.robot.oi.unidirectional.OIUnidirectional;
1112
import org.usfirst.frc.team449.robot.other.BufferTimer;
@@ -32,6 +33,11 @@ public class UnidirectionalNavXShiftingDefaultDrive<T extends YamlSubsystem & Dr
3233
@NotNull
3334
protected final AutoshiftComponent autoshiftComponent;
3435

36+
/**
37+
* The coefficient to multiply the loop output by in high gear.
38+
*/
39+
private final double highGearAngularCoefficient;
40+
3541
/**
3642
* Default constructor
3743
*
@@ -55,6 +61,7 @@ public class UnidirectionalNavXShiftingDefaultDrive<T extends YamlSubsystem & Dr
5561
* @param subsystem The drive to execute this command on.
5662
* @param oi The OI controlling the robot.
5763
* @param autoshiftComponent The helper object for autoshifting.
64+
* @param highGearAngularCoefficient The coefficient to multiply the loop output by in high gear. Defaults to 1.
5865
*/
5966
@JsonCreator
6067
public UnidirectionalNavXShiftingDefaultDrive(@JsonProperty(required = true) double absoluteTolerance,
@@ -63,17 +70,19 @@ public UnidirectionalNavXShiftingDefaultDrive(@JsonProperty(required = true) dou
6370
double deadband,
6471
@Nullable Double maxAngularVelToEnterLoop,
6572
boolean inverted,
66-
int kP,
67-
int kI,
68-
int kD,
73+
double kP,
74+
double kI,
75+
double kD,
6976
@NotNull @JsonProperty(required = true) BufferTimer driveStraightLoopEntryTimer,
7077
@NotNull @JsonProperty(required = true) T subsystem,
7178
@NotNull @JsonProperty(required = true) OIUnidirectional oi,
72-
@NotNull @JsonProperty(required = true) AutoshiftComponent autoshiftComponent) {
79+
@NotNull @JsonProperty(required = true) AutoshiftComponent autoshiftComponent,
80+
Double highGearAngularCoefficient) {
7381
super(absoluteTolerance, toleranceBuffer, minimumOutput, maximumOutput, deadband, maxAngularVelToEnterLoop,
7482
inverted, kP, kI, kD, driveStraightLoopEntryTimer, subsystem, oi);
7583
this.autoshiftComponent = autoshiftComponent;
7684
this.subsystem = subsystem;
85+
this.highGearAngularCoefficient = highGearAngularCoefficient != null ? highGearAngularCoefficient : 1;
7786
}
7887

7988
/**
@@ -105,4 +114,14 @@ protected void interrupted() {
105114
Logger.addEvent("ShiftingUnidirectionalNavXArcadeDrive Interrupted! Stopping the robot.", this.getClass());
106115
subsystem.fullStop();
107116
}
117+
118+
/**
119+
* Give the correct output to the motors based on whether we're in free drive or drive straight.
120+
*
121+
* @param output The output of the angular PID loop.
122+
*/
123+
@Override
124+
protected void usePIDOutput(double output) {
125+
super.usePIDOutput(output * (subsystem.getGear() == Shiftable.gear.HIGH.getNumVal() ? highGearAngularCoefficient : 1));
126+
}
108127
}

RoboRIO/src/main/java/org/usfirst/frc/team449/robot/drive/unidirectional/DriveTalonCluster.java

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -196,6 +196,8 @@ public String[] getHeader() {
196196
"right_voltage",
197197
"left_pos",
198198
"right_pos",
199+
"left_error",
200+
"right_error",
199201
"raw_angle"};
200202
}
201203

@@ -217,6 +219,8 @@ public Object[] getData() {
217219
rightMaster.getOutputVoltage(),
218220
leftMaster.getPositionFeet(),
219221
rightMaster.getPositionFeet(),
222+
leftMaster.getError(),
223+
rightMaster.getError(),
220224
navX.getAngle()};
221225
}
222226

RoboRIO/src/main/java/org/usfirst/frc/team449/robot/jacksonWrappers/FPSTalon.java

Lines changed: 3 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -98,7 +98,6 @@ public class FPSTalon implements SimpleMotor, Shiftable {
9898
* Default constructor.
9999
*
100100
* @param port CAN port of this Talon.
101-
* @param inverted Whether this Talon is inverted.
102101
* @param reverseOutput Whether to reverse the output (identical effect to inverting outside of
103102
* position PID)
104103
* @param enableBrakeMode Whether to brake or coast when stopped.
@@ -136,7 +135,6 @@ public class FPSTalon implements SimpleMotor, Shiftable {
136135
*/
137136
@JsonCreator
138137
public FPSTalon(@JsonProperty(required = true) int port,
139-
@JsonProperty(required = true) boolean inverted,
140138
boolean reverseOutput,
141139
@JsonProperty(required = true) boolean enableBrakeMode,
142140
@Nullable Boolean fwdLimitSwitchNormallyOpen,
@@ -160,8 +158,8 @@ public FPSTalon(@JsonProperty(required = true) int port,
160158
canTalon = new CANTalon(port);
161159
//Set this to false because we only use reverseOutput for slaves.
162160
canTalon.reverseOutput(reverseOutput);
163-
//Set inversion
164-
canTalon.setInverted(inverted);
161+
//NO TOUCHY
162+
canTalon.setInverted(false);
165163
//Set brake mode
166164
canTalon.enableBrakeMode(enableBrakeMode);
167165

@@ -559,7 +557,7 @@ public void setGearScaledVelocity(double velocity, Shiftable.gear gear) {
559557
* @return the position of the talon in feet, or null of inches per rotation wasn't given.
560558
*/
561559
public Double getPositionFeet() {
562-
return encoderToFeet(canTalon.getEncPosition());
560+
return encoderToFeet(canTalon.getPosition());
563561
}
564562

565563
/**

RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/interfaces/navX/commands/PIDAngleCommand.java

Lines changed: 11 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -99,7 +99,7 @@ public PIDAngleCommand(@JsonProperty(required = true) double absoluteTolerance,
9999
}
100100

101101
/**
102-
* Process the output of the PID loop to account for minimum output, deadband, and inversion.
102+
* Process the output of the PID loop to account for minimum output and inversion.
103103
*
104104
* @param output The output from the WPILib angular PID loop.
105105
* @return The processed output, ready to be subtracted from the left side of the drive output and added to the
@@ -112,17 +112,23 @@ protected double processPIDOutput(double output) {
112112
} else if (output < 0 && output > -minimumOutput) {
113113
output = -minimumOutput;
114114
}
115-
//Set the output to 0 if we're within the deadband.
116-
if (Math.abs(this.getPIDController().getError()) < deadband) {
117-
output = 0;
118-
}
119115
if (inverted) {
120116
output *= -1;
121117
}
122118

123119
return output;
124120
}
125121

122+
/**
123+
* Deadband the output of the PID loop.
124+
*
125+
* @param output The output from the WPILib angular PID loop.
126+
* @return That output after being deadbanded with the map-given deadband.
127+
*/
128+
protected double deadbandOutput(double output){
129+
return this.getPIDController().getError() > deadband ? output : 0;
130+
}
131+
126132
/**
127133
* Returns the input for the pid loop. <p> It returns the input for the pid loop, so if this command was based off
128134
* of a gyro, then it should return the angle of the gyro </p> <p> All subclasses of {@link PIDCommand} must

RoboRIO/src/main/resources/calcifer_map.yml

Lines changed: 3 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -113,7 +113,6 @@ drive:
113113
&leftMaster
114114
'@id': leftMaster
115115
port: 7
116-
inverted: false
117116
reverseOutput: true
118117
enableBrakeMode: false
119118
feetPerRotation: 0.9817
@@ -128,7 +127,7 @@ drive:
128127
fwdPeakOutputVoltage: 12
129128
fwdNominalOutputVoltage: 0.7
130129
maxSpeed: 6.2
131-
kP: 0.3
130+
kP: 0.5
132131
kI: 0.0
133132
kD: 0.0
134133
motionProfileP: 1.5
@@ -141,7 +140,6 @@ drive:
141140
kP: 0.7
142141
kI: 0.0
143142
kD: 3.0
144-
maxClosedLoopVoltage: 12
145143
updaterProcessPeriodSecs: 0.005
146144
minNumPointsInBottomBuffer: 10
147145
slaves:
@@ -155,7 +153,6 @@ drive:
155153
org.usfirst.frc.team449.robot.jacksonWrappers.FPSTalon:
156154
<<: *leftMaster
157155
'@id': rightMaster
158-
inverted: false
159156
reverseSensor: true
160157
reverseOutput: false
161158
port: 2
@@ -191,12 +188,12 @@ defaultDriveCommand:
191188
kP: 0.012
192189
kI: 0.0
193190
kD: 0.0
194-
absoluteTolerance: 1
195-
maximumOutput: 0.33333
191+
absoluteTolerance: 0
196192
toleranceBuffer: 25
197193
deadband: 2
198194
maxAngularVelToEnterLoop: 0.05
199195
inverted: true
196+
highGearAngularCoefficient: 2
200197
driveStraightLoopEntryTimer:
201198
'@id': driveStraightLoopEntryTimer
202199
bufferTimeSeconds: 0.15
@@ -224,7 +221,6 @@ climber:
224221
org.usfirst.frc.team449.robot.jacksonWrappers.FPSTalon:
225222
'@id': climberTalon
226223
port: 5
227-
inverted: false
228224
enableBrakeMode: false
229225
maxPower: 500
230226
simpleMotor:

docs/allclasses-frame.html

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -2,10 +2,10 @@
22
<!-- NewPage -->
33
<html lang="en">
44
<head>
5-
<!-- Generated by javadoc (9) on Fri Oct 06 23:23:54 EDT 2017 -->
5+
<!-- Generated by javadoc (9) on Sat Oct 07 23:03:52 EDT 2017 -->
66
<title>All Classes (RoboRIO 1.0 API)</title>
77
<meta http-equiv="Content-Type" content="text/html; charset=utf-8">
8-
<meta name="date" content="2017-10-06">
8+
<meta name="date" content="2017-10-07">
99
<link rel="stylesheet" type="text/css" href="stylesheet.css" title="Style">
1010
<link rel="stylesheet" type="text/css" href="jquery/jquery-ui.css" title="Style">
1111
<script type="text/javascript" src="script.js"></script>

docs/allclasses-noframe.html

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -2,10 +2,10 @@
22
<!-- NewPage -->
33
<html lang="en">
44
<head>
5-
<!-- Generated by javadoc (9) on Fri Oct 06 23:23:54 EDT 2017 -->
5+
<!-- Generated by javadoc (9) on Sat Oct 07 23:03:52 EDT 2017 -->
66
<title>All Classes (RoboRIO 1.0 API)</title>
77
<meta http-equiv="Content-Type" content="text/html; charset=utf-8">
8-
<meta name="date" content="2017-10-06">
8+
<meta name="date" content="2017-10-07">
99
<link rel="stylesheet" type="text/css" href="stylesheet.css" title="Style">
1010
<link rel="stylesheet" type="text/css" href="jquery/jquery-ui.css" title="Style">
1111
<script type="text/javascript" src="script.js"></script>

docs/constant-values.html

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -2,10 +2,10 @@
22
<!-- NewPage -->
33
<html lang="en">
44
<head>
5-
<!-- Generated by javadoc (9) on Fri Oct 06 23:23:54 EDT 2017 -->
5+
<!-- Generated by javadoc (9) on Sat Oct 07 23:03:51 EDT 2017 -->
66
<title>Constant Field Values (RoboRIO 1.0 API)</title>
77
<meta http-equiv="Content-Type" content="text/html; charset=utf-8">
8-
<meta name="date" content="2017-10-06">
8+
<meta name="date" content="2017-10-07">
99
<link rel="stylesheet" type="text/css" href="stylesheet.css" title="Style">
1010
<link rel="stylesheet" type="text/css" href="jquery/jquery-ui.css" title="Style">
1111
<script type="text/javascript" src="script.js"></script>

0 commit comments

Comments
 (0)