Skip to content

Commit

Permalink
Merge in master
Browse files Browse the repository at this point in the history
  • Loading branch information
Noah Gleason committed Oct 16, 2017
2 parents 5c177e7 + 03e3abb commit 0334f8e
Show file tree
Hide file tree
Showing 334 changed files with 4,698 additions and 45,590 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -76,9 +76,9 @@ public UnidirectionalNavXDefaultDrive(@JsonProperty(required = true) double abso
double deadband,
@Nullable Double maxAngularVelToEnterLoop,
boolean inverted,
int kP,
int kI,
int kD,
double kP,
double kI,
double kD,
@NotNull @JsonProperty(required = true) BufferTimer driveStraightLoopEntryTimer,
@NotNull @JsonProperty(required = true) T subsystem,
@NotNull @JsonProperty(required = true) OIUnidirectional oi) {
Expand Down Expand Up @@ -177,6 +177,11 @@ protected void usePIDOutput(double output) {
//Process the output (minimumOutput, deadband, etc.)
output = processPIDOutput(output);

//Deadband if we're stationary
if(oi.getLeftOutput() == 0 || oi.getRightOutput() == 0){
output=deadbandOutput(output);
}

//Adjust the heading according to the PID output, it'll be positive if we want to go right.
subsystem.setOutput(oi.getLeftOutput() - output, oi.getRightOutput() + output);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
import org.usfirst.frc.team449.robot.components.NavXRumbleComponent;
import org.usfirst.frc.team449.robot.drive.shifting.DriveShiftable;
import org.usfirst.frc.team449.robot.drive.unidirectional.DriveUnidirectional;
import org.usfirst.frc.team449.robot.generalInterfaces.shiftable.Shiftable;
import org.usfirst.frc.team449.robot.jacksonWrappers.YamlSubsystem;
import org.usfirst.frc.team449.robot.oi.unidirectional.OIUnidirectional;
import org.usfirst.frc.team449.robot.other.BufferTimer;
Expand All @@ -33,6 +34,11 @@ public class UnidirectionalNavXShiftingDefaultDrive <T extends YamlSubsystem & D
@NotNull
protected final AutoshiftComponent autoshiftComponent;

/**
* The coefficient to multiply the loop output by in high gear.
*/
private final double highGearAngularCoefficient;

/**
* Default constructor
*
Expand All @@ -56,6 +62,7 @@ public class UnidirectionalNavXShiftingDefaultDrive <T extends YamlSubsystem & D
* @param subsystem The drive to execute this command on.
* @param oi The OI controlling the robot.
* @param autoshiftComponent The helper object for autoshifting.
* @param highGearAngularCoefficient The coefficient to multiply the loop output by in high gear. Defaults to 1.
*/
@JsonCreator
public UnidirectionalNavXShiftingDefaultDrive(@JsonProperty(required = true) double absoluteTolerance,
Expand All @@ -64,17 +71,19 @@ public UnidirectionalNavXShiftingDefaultDrive(@JsonProperty(required = true) dou
double deadband,
@Nullable Double maxAngularVelToEnterLoop,
boolean inverted,
int kP,
int kI,
int kD,
double kP,
double kI,
double kD,
@NotNull @JsonProperty(required = true) BufferTimer driveStraightLoopEntryTimer,
@NotNull @JsonProperty(required = true) T subsystem,
@NotNull @JsonProperty(required = true) OIUnidirectional oi,
@NotNull @JsonProperty(required = true) AutoshiftComponent autoshiftComponent) {
@NotNull @JsonProperty(required = true) AutoshiftComponent autoshiftComponent,
Double highGearAngularCoefficient) {
super(absoluteTolerance, toleranceBuffer, minimumOutput, maximumOutput, deadband, maxAngularVelToEnterLoop,
inverted, kP, kI, kD, driveStraightLoopEntryTimer, subsystem, oi);
this.autoshiftComponent = autoshiftComponent;
this.subsystem = subsystem;
this.highGearAngularCoefficient = highGearAngularCoefficient != null ? highGearAngularCoefficient : 1;
}

/**
Expand Down Expand Up @@ -106,4 +115,14 @@ protected void interrupted() {
Logger.addEvent("ShiftingUnidirectionalNavXArcadeDrive Interrupted! Stopping the robot.", this.getClass());
subsystem.fullStop();
}

/**
* Give the correct output to the motors based on whether we're in free drive or drive straight.
*
* @param output The output of the angular PID loop.
*/
@Override
protected void usePIDOutput(double output) {
super.usePIDOutput(output * (subsystem.getGear() == Shiftable.gear.HIGH.getNumVal() ? highGearAngularCoefficient : 1));
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -219,6 +219,8 @@ public String[] getHeader() {
"right_voltage",
"left_pos",
"right_pos",
"left_error",
"right_error",
"heading",
"rotational_velocity",
"raw_angle",
Expand All @@ -244,6 +246,8 @@ public Object[] getData() {
rightMaster.getOutputVoltage(),
leftMaster.getPositionFeet(),
rightMaster.getPositionFeet(),
leftMaster.getError(),
rightMaster.getError(),
navX.pidGet(),
navX.getRate(),
navX.getAngle(),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -171,7 +171,7 @@ public FPSTalon(@JsonProperty(required = true) int port,
canTalon = new CANTalon(port, controlFrameRateMillis != null ? controlFrameRateMillis : 10);
//Set this to false because we only use reverseOutput for slaves.
canTalon.reverseOutput(reverseOutput);
//DONT TOUCH THIS SHIT
//NO TOUCHY
canTalon.setInverted(false);
//Set brake mode
canTalon.enableBrakeMode(enableBrakeMode);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -99,7 +99,7 @@ public PIDAngleCommand(@JsonProperty(required = true) double absoluteTolerance,
}

/**
* Process the output of the PID loop to account for minimum output, deadband, and inversion.
* Process the output of the PID loop to account for minimum output and inversion.
*
* @param output The output from the WPILib angular PID loop.
* @return The processed output, ready to be subtracted from the left side of the drive output and added to the
Expand All @@ -112,17 +112,23 @@ protected double processPIDOutput(double output) {
} else if (output < 0 && output > -minimumOutput) {
output = -minimumOutput;
}
//Set the output to 0 if we're within the deadband.
if (Math.abs(this.getPIDController().getError()) < deadband) {
output = 0;
}
if (inverted) {
output *= -1;
}

return output;
}

/**
* Deadband the output of the PID loop.
*
* @param output The output from the WPILib angular PID loop.
* @return That output after being deadbanded with the map-given deadband.
*/
protected double deadbandOutput(double output){
return this.getPIDController().getError() > deadband ? output : 0;
}

/**
* Returns the input for the pid loop. <p> It returns the input for the pid loop, so if this command was based off
* of a gyro, then it should return the angle of the gyro </p> <p> All subclasses of {@link PIDCommand} must
Expand Down
10 changes: 3 additions & 7 deletions RoboRIO/src/main/resources/calcifer_map.yml
Original file line number Diff line number Diff line change
Expand Up @@ -114,7 +114,6 @@ drive:
&leftMaster
'@id': leftMaster
port: 7
inverted: false
reverseOutput: true
enableBrakeMode: false
feetPerRotation: 0.9817
Expand All @@ -129,7 +128,7 @@ drive:
fwdPeakOutputVoltage: 12
fwdNominalOutputVoltage: 0.7
maxSpeed: 6.2
kP: 0.3
kP: 0.5
kI: 0.0
kD: 0.0
motionProfilePFwd: 1.5
Expand All @@ -142,7 +141,6 @@ drive:
kP: 0.7
kI: 0.0
kD: 3.0
maxClosedLoopVoltage: 12
updaterProcessPeriodSecs: 0.005
minNumPointsInBottomBuffer: 10
slaves:
Expand All @@ -156,7 +154,6 @@ drive:
org.usfirst.frc.team449.robot.jacksonWrappers.FPSTalon:
<<: *leftMaster
'@id': rightMaster
inverted: false
reverseSensor: true
reverseOutput: false
port: 2
Expand Down Expand Up @@ -192,12 +189,12 @@ defaultDriveCommand:
kP: 0.012
kI: 0.0
kD: 0.0
absoluteTolerance: 1
maximumOutput: 0.33333
absoluteTolerance: 0
toleranceBuffer: 25
deadband: 2
maxAngularVelToEnterLoop: 0.05
inverted: true
highGearAngularCoefficient: 2
driveStraightLoopEntryTimer:
'@id': driveStraightLoopEntryTimer
bufferTimeSeconds: 0.15
Expand Down Expand Up @@ -225,7 +222,6 @@ climber:
org.usfirst.frc.team449.robot.jacksonWrappers.FPSTalon:
'@id': climberTalon
port: 5
inverted: false
enableBrakeMode: false
maxPower: 500
simpleMotor:
Expand Down
13 changes: 2 additions & 11 deletions docs/allclasses-frame.html
Original file line number Diff line number Diff line change
Expand Up @@ -2,20 +2,11 @@
<!-- NewPage -->
<html lang="en">
<head>
<!-- Generated by javadoc (9) on Sat Oct 14 18:57:33 EDT 2017 -->
<!-- Generated by javadoc (1.8.0_111) on Sun Oct 15 21:56:20 EDT 2017 -->
<title>All Classes (RoboRIO 1.0 API)</title>
<meta http-equiv="Content-Type" content="text/html; charset=utf-8">
<meta name="date" content="2017-10-14">
<meta name="date" content="2017-10-15">
<link rel="stylesheet" type="text/css" href="stylesheet.css" title="Style">
<link rel="stylesheet" type="text/css" href="jquery/jquery-ui.css" title="Style">
<script type="text/javascript" src="script.js"></script>
<script type="text/javascript" src="jquery/jszip/dist/jszip.min.js"></script>
<script type="text/javascript" src="jquery/jszip-utils/dist/jszip-utils.min.js"></script>
<!--[if IE]>
<script type="text/javascript" src="jquery/jszip-utils/dist/jszip-utils-ie.min.js"></script>
<![endif]-->
<script type="text/javascript" src="jquery/jquery-1.10.2.js"></script>
<script type="text/javascript" src="jquery/jquery-ui.js"></script>
</head>
<body>
<h1 class="bar">All&nbsp;Classes</h1>
Expand Down
13 changes: 2 additions & 11 deletions docs/allclasses-noframe.html
Original file line number Diff line number Diff line change
Expand Up @@ -2,20 +2,11 @@
<!-- NewPage -->
<html lang="en">
<head>
<!-- Generated by javadoc (9) on Sat Oct 14 18:57:33 EDT 2017 -->
<!-- Generated by javadoc (1.8.0_111) on Sun Oct 15 21:56:20 EDT 2017 -->
<title>All Classes (RoboRIO 1.0 API)</title>
<meta http-equiv="Content-Type" content="text/html; charset=utf-8">
<meta name="date" content="2017-10-14">
<meta name="date" content="2017-10-15">
<link rel="stylesheet" type="text/css" href="stylesheet.css" title="Style">
<link rel="stylesheet" type="text/css" href="jquery/jquery-ui.css" title="Style">
<script type="text/javascript" src="script.js"></script>
<script type="text/javascript" src="jquery/jszip/dist/jszip.min.js"></script>
<script type="text/javascript" src="jquery/jszip-utils/dist/jszip-utils.min.js"></script>
<!--[if IE]>
<script type="text/javascript" src="jquery/jszip-utils/dist/jszip-utils-ie.min.js"></script>
<![endif]-->
<script type="text/javascript" src="jquery/jquery-1.10.2.js"></script>
<script type="text/javascript" src="jquery/jquery-ui.js"></script>
</head>
<body>
<h1 class="bar">All&nbsp;Classes</h1>
Expand Down
40 changes: 6 additions & 34 deletions docs/constant-values.html
Original file line number Diff line number Diff line change
Expand Up @@ -2,20 +2,11 @@
<!-- NewPage -->
<html lang="en">
<head>
<!-- Generated by javadoc (9) on Sat Oct 14 18:57:33 EDT 2017 -->
<!-- Generated by javadoc (1.8.0_111) on Sun Oct 15 21:56:20 EDT 2017 -->
<title>Constant Field Values (RoboRIO 1.0 API)</title>
<meta http-equiv="Content-Type" content="text/html; charset=utf-8">
<meta name="date" content="2017-10-14">
<meta name="date" content="2017-10-15">
<link rel="stylesheet" type="text/css" href="stylesheet.css" title="Style">
<link rel="stylesheet" type="text/css" href="jquery/jquery-ui.css" title="Style">
<script type="text/javascript" src="script.js"></script>
<script type="text/javascript" src="jquery/jszip/dist/jszip.min.js"></script>
<script type="text/javascript" src="jquery/jszip-utils/dist/jszip-utils.min.js"></script>
<!--[if IE]>
<script type="text/javascript" src="jquery/jszip-utils/dist/jszip-utils-ie.min.js"></script>
<![endif]-->
<script type="text/javascript" src="jquery/jquery-1.10.2.js"></script>
<script type="text/javascript" src="jquery/jquery-ui.js"></script>
</head>
<body>
<script type="text/javascript"><!--
Expand All @@ -27,11 +18,10 @@
catch(err) {
}
//-->
var pathtoroot = "./";loadScripts(document, 'script');</script>
</script>
<noscript>
<div>JavaScript is disabled on your browser.</div>
</noscript>
<div class="fixedNav">
<!-- ========= START OF TOP NAVBAR ======= -->
<div class="topNav"><a name="navbar.top">
<!-- -->
Expand Down Expand Up @@ -62,12 +52,6 @@
<ul class="navList" id="allclasses_navbar_top">
<li><a href="allclasses-noframe.html">All&nbsp;Classes</a></li>
</ul>
<ul class="navListSearch">
<li><span>SEARCH:&nbsp;</span>
<input type="text" id="search" value=" " disabled="disabled">
<input type="reset" id="reset" value=" " disabled="disabled">
</li>
</ul>
<div>
<script type="text/javascript"><!--
allClassesLink = document.getElementById("allclasses_navbar_top");
Expand All @@ -79,20 +63,11 @@
}
//-->
</script>
<noscript>
<div>JavaScript is disabled on your browser.</div>
</noscript>
</div>
<a name="skip.navbar.top">
<!-- -->
</a></div>
<!-- ========= END OF TOP NAVBAR ========= -->
</div>
<div class="navPadding">&nbsp;</div>
<script type="text/javascript"><!--
$('.navPadding').css('padding-top', $('.fixedNav').css("height"));
//-->
</script>
<div class="header">
<h1 title="Constant Field Values" class="title">Constant Field Values</h1>
<h2 title="Contents">Contents</h2>
Expand All @@ -106,19 +81,19 @@ <h2 title="Contents">Contents</h2>
<h2 title="org.usfirst">org.usfirst.*</h2>
<ul class="blockList">
<li class="blockList">
<table class="constantsSummary" summary="Constant Field Values table, listing constant fields, and values">
<table class="constantsSummary" border="0" cellpadding="3" cellspacing="0" summary="Constant Field Values table, listing constant fields, and values">
<caption><span>org.usfirst.frc.team449.robot.<a href="org/usfirst/frc/team449/robot/Robot.html" title="class in org.usfirst.frc.team449.robot">Robot</a></span><span class="tabEnd">&nbsp;</span></caption>
<tr>
<th class="colFirst" scope="col">Modifier and Type</th>
<th class="colSecond" scope="col">Constant Field</th>
<th scope="col">Constant Field</th>
<th class="colLast" scope="col">Value</th>
</tr>
<tbody>
<tr class="altColor">
<td class="colFirst"><a name="org.usfirst.frc.team449.robot.Robot.RESOURCES_PATH">
<!-- -->
</a><code>public&nbsp;static&nbsp;final&nbsp;java.lang.String</code></td>
<th class="colSecond" scope="row"><code><a href="org/usfirst/frc/team449/robot/Robot.html#RESOURCES_PATH">RESOURCES_PATH</a></code></th>
<td><code><a href="org/usfirst/frc/team449/robot/Robot.html#RESOURCES_PATH">RESOURCES_PATH</a></code></td>
<td class="colLast"><code>"/home/lvuser/449_resources/"</code></td>
</tr>
</tbody>
Expand Down Expand Up @@ -167,9 +142,6 @@ <h2 title="org.usfirst">org.usfirst.*</h2>
}
//-->
</script>
<noscript>
<div>JavaScript is disabled on your browser.</div>
</noscript>
</div>
<a name="skip.navbar.bottom">
<!-- -->
Expand Down
Loading

0 comments on commit 0334f8e

Please sign in to comment.