summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorLuke Shumaker <lukeshu@sbcglobal.net>2016-01-16 12:56:01 -0500
committerLuke Shumaker <lukeshu@sbcglobal.net>2016-01-16 12:56:01 -0500
commit0e7c82c6173c0d230c1a921150d691bd8ebfde7d (patch)
tree8eb9f1d3465d3a81e12393cae4e0bbcfa690beef
parent75c2407dd85a69b8f80e9b376da1bfb9ed0bb173 (diff)
trailing whitespace cleanup
-rw-r--r--src/org/mckenzierobotics/lib/robot/CommandBase.java16
-rw-r--r--src/org/mckenzierobotics/lib/robot/CommandRobot.java12
-rw-r--r--src/org/mckenzierobotics/lib/robot/FeedForward.java14
-rw-r--r--src/org/mckenzierobotics/lib/robot/PIDController.java18
-rw-r--r--src/org/mckenzierobotics/lib/robot/PIDOutputSplitter.java12
-rw-r--r--src/org/mckenzierobotics/lib/robot/PIDServo.java2
-rw-r--r--src/org/mckenzierobotics/lib/robot/RateLimitedPIDOutput.java8
-rw-r--r--src/org/mckenzierobotics/lib/robot/RollingAvg.java8
-rw-r--r--src/org/mckenzierobotics/lib/robot/SendablePIDOutput.java8
-rw-r--r--src/org/usfirst/frc/team4272/robot2016/Autonomous.java2
-rw-r--r--src/org/usfirst/frc/team4272/robot2016/HwRobot.java4
-rw-r--r--src/org/usfirst/frc/team4272/robot2016/Teleop.java2
-rw-r--r--src/org/usfirst/frc/team4272/robotlib/DoubleSolenoid.java10
-rw-r--r--src/org/usfirst/frc/team4272/robotlib/LimitSwitchedPIDOutput.java6
-rw-r--r--src/org/usfirst/frc/team4272/robotlib/Xbox360Controller.java10
15 files changed, 66 insertions, 66 deletions
diff --git a/src/org/mckenzierobotics/lib/robot/CommandBase.java b/src/org/mckenzierobotics/lib/robot/CommandBase.java
index 0e70893..a0fb5a2 100644
--- a/src/org/mckenzierobotics/lib/robot/CommandBase.java
+++ b/src/org/mckenzierobotics/lib/robot/CommandBase.java
@@ -1,18 +1,18 @@
/**
* CommandBase - defines robot hardware; superclass of all commands.
- *
+ *
* Copyright (c) FIRST 2008. All Rights Reserved.
* Open Source Software - may be modified and shared by FRC teams. The code
* must be accompanied by the FIRST BSD license file in the root directory of
* the project.
- *
+ *
* Copyright (c) 2012 Precise Path Robotics, Inc
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
- *
+ *
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
@@ -20,7 +20,7 @@
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
- *
+ *
* @author Luke Shumaker <lukeshu@sbcglobal.net>
*/
package org.mckenzierobotics.lib.robot;
@@ -33,7 +33,7 @@ import edu.wpi.first.wpilibj.command.Subsystem;
* The base for all commands, also the class defining robot hardware/config.
* All atomic commands should subclass CommandBase. CommandBase stores creates
* and stores each control system.
- *
+ *
* @author Luke Shumaker <lukeshu@sbcglobal.net>
*/
public abstract class CommandBase extends Command {
@@ -45,14 +45,14 @@ public abstract class CommandBase extends Command {
}
super.requires(subsystem);
}
-
+
public synchronized void start() {
if (has_subsystems) { super.start(); }
}
/**
* Instantiate a CANJaguar, handling exceptions.
- *
+ *
* @param id CANJaguar ID to use.
* @return the CANJaguar
*/
@@ -65,7 +65,7 @@ public abstract class CommandBase extends Command {
}
return ret;
}
-
+
public CommandBase() { super(); }
public CommandBase(double timeout) { super(timeout); }
public CommandBase(String name) { super(name); }
diff --git a/src/org/mckenzierobotics/lib/robot/CommandRobot.java b/src/org/mckenzierobotics/lib/robot/CommandRobot.java
index 35534c2..ecbd879 100644
--- a/src/org/mckenzierobotics/lib/robot/CommandRobot.java
+++ b/src/org/mckenzierobotics/lib/robot/CommandRobot.java
@@ -1,13 +1,13 @@
/**
* CommandFramework base class for FRC 1024.
- *
+ *
* Copyright (c) 2012 Precise Path Robotics, Inc
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
- *
+ *
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
@@ -15,7 +15,7 @@
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
- *
+ *
* @author Luke Shumaker <lukeshu@sbcglobal.net>
*/
@@ -31,14 +31,14 @@ import edu.wpi.first.wpilibj.command.Scheduler;
* documentation. If you change the name of this class or the package after
* creating this project, you must also update the manifest file in the resource
* directory.
- *
+ *
* @author Luke Shumaker <lukeshu@sbcglobal.net>
*/
public abstract class CommandRobot extends IterativeRobot {
protected Command autonomousCommand;
protected Command teleopCommand;
-
+
public abstract void robotInit();
public void autonomousInit() {
@@ -57,7 +57,7 @@ public abstract class CommandRobot extends IterativeRobot {
public void teleopPeriodic() {
Scheduler.getInstance().run();
}
-
+
public void disabledInit() {
autonomousCommand.cancel();
teleopCommand.cancel();
diff --git a/src/org/mckenzierobotics/lib/robot/FeedForward.java b/src/org/mckenzierobotics/lib/robot/FeedForward.java
index a18dccc..c7a06b8 100644
--- a/src/org/mckenzierobotics/lib/robot/FeedForward.java
+++ b/src/org/mckenzierobotics/lib/robot/FeedForward.java
@@ -5,7 +5,7 @@
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
- *
+ *
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
@@ -13,7 +13,7 @@
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
- *
+ *
* @author Luke Shumaker <lukeshu@sbcglobal.net>
*/
package org.mckenzierobotics.lib.robot;
@@ -45,7 +45,7 @@ public abstract class FeedForward implements PIDOutput {
pidOutput = output;
pid = new PIDController(Kp, Ki, Kd, source, new PIDTrigger(this), period);
}
-
+
public FeedForward(double Kp, double Ki, double Kd, PIDSource source, PIDOutput output, boolean autodisable) {
pidOutput = output;
pid = new PIDController(Kp, Ki, Kd, source, new PIDTrigger(this), autodisable);
@@ -54,15 +54,15 @@ public abstract class FeedForward implements PIDOutput {
pidOutput = output;
pid = new PIDController(Kp, Ki, Kd, source, new PIDTrigger(this), period, autodisable);
}
-
+
public PIDController getPID() {
return pid;
}
-
+
public void pidWrite(double output) {
pid.setSetpoint(output);
}
-
+
public void update(double pidResult) {
if (pid.isEnabled()) {
double ffResult = calculate(pid.getSetpoint());
@@ -71,6 +71,6 @@ public abstract class FeedForward implements PIDOutput {
pidOutput.pidWrite(0);
}
}
-
+
public abstract double calculate(double setpoint);
}
diff --git a/src/org/mckenzierobotics/lib/robot/PIDController.java b/src/org/mckenzierobotics/lib/robot/PIDController.java
index e2f8087..b0cf99f 100644
--- a/src/org/mckenzierobotics/lib/robot/PIDController.java
+++ b/src/org/mckenzierobotics/lib/robot/PIDController.java
@@ -15,15 +15,15 @@
*
* THIS SOFTWARE IS PROVIDED BY FIRST AND CONTRIBUTORS``AS IS'' AND ANY
* EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
- * WARRANTIES OF MERCHANTABILITY NONINFRINGEMENT AND FITNESS FOR A PARTICULAR
- * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL FIRST OR CONTRIBUTORS BE LIABLE FOR
+ * WARRANTIES OF MERCHANTABILITY NONINFRINGEMENT AND FITNESS FOR A PARTICULAR
+ * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL FIRST OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
- *
+ *
* @author Luke Shumaker <lukeshu@sbcglobal.net>
*/
package org.mckenzierobotics.lib.robot;
@@ -56,7 +56,7 @@ public class PIDController extends edu.wpi.first.wpilibj.PIDController implement
this.source = source;
this.output = output;
}
-
+
public PIDController(double Kp, double Ki, double Kd, PIDSource source, PIDOutput output, boolean autodisable) {
super(Kp, Ki, Kd, source, output);
this.autodisable = autodisable;
@@ -71,7 +71,7 @@ public class PIDController extends edu.wpi.first.wpilibj.PIDController implement
this.source = source;
this.output = output;
}
-
+
public void setSetpoint(double output) {
if ((output == 0) && autodisable) {
disable();
@@ -84,19 +84,19 @@ public class PIDController extends edu.wpi.first.wpilibj.PIDController implement
super.setSetpoint(output);
}
}
-
+
public void pidWrite(double output) {
setSetpoint(output);
}
-
+
public void set(double output) {
setSetpoint(output);
}
-
+
/**
* Don't use this; it is leaking up from CANJaguar
* @param output
- * @param syncGroup
+ * @param syncGroup
*/
public void set(double output, byte syncGroup) {
setSetpoint(output);
diff --git a/src/org/mckenzierobotics/lib/robot/PIDOutputSplitter.java b/src/org/mckenzierobotics/lib/robot/PIDOutputSplitter.java
index b4e7713..c689bab 100644
--- a/src/org/mckenzierobotics/lib/robot/PIDOutputSplitter.java
+++ b/src/org/mckenzierobotics/lib/robot/PIDOutputSplitter.java
@@ -15,15 +15,15 @@
*
* THIS SOFTWARE IS PROVIDED BY FIRST AND CONTRIBUTORS``AS IS'' AND ANY
* EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
- * WARRANTIES OF MERCHANTABILITY NONINFRINGEMENT AND FITNESS FOR A PARTICULAR
- * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL FIRST OR CONTRIBUTORS BE LIABLE FOR
+ * WARRANTIES OF MERCHANTABILITY NONINFRINGEMENT AND FITNESS FOR A PARTICULAR
+ * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL FIRST OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
- *
+ *
* @author Luke Shumaker <lukeshu@sbcglobal.net>
*/
@@ -65,13 +65,13 @@ public class PIDOutputSplitter implements PIDOutput {
}
}
}
-
+
/**
* Handles exceptions from pidWrite().
- *
+ *
* By default it writes to System.out; you may extend+override this to
* change the behavior.
- *
+ *
* @param e Exception
*/
public void error(Exception e) {
diff --git a/src/org/mckenzierobotics/lib/robot/PIDServo.java b/src/org/mckenzierobotics/lib/robot/PIDServo.java
index fdbd1ce..9d038d1 100644
--- a/src/org/mckenzierobotics/lib/robot/PIDServo.java
+++ b/src/org/mckenzierobotics/lib/robot/PIDServo.java
@@ -29,7 +29,7 @@ public class PIDServo extends Servo implements PIDOutput {
public PIDServo(int channel) {
super(channel);
}
-
+
public void pidWrite(double degrees) {
setAngle(getAngle()+degrees);
}
diff --git a/src/org/mckenzierobotics/lib/robot/RateLimitedPIDOutput.java b/src/org/mckenzierobotics/lib/robot/RateLimitedPIDOutput.java
index ed36345..10f01ce 100644
--- a/src/org/mckenzierobotics/lib/robot/RateLimitedPIDOutput.java
+++ b/src/org/mckenzierobotics/lib/robot/RateLimitedPIDOutput.java
@@ -5,7 +5,7 @@
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
- *
+ *
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
@@ -13,7 +13,7 @@
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
- *
+ *
* @author Luke Shumaker <lukeshu@sbcglobal.net>
*/
@@ -31,12 +31,12 @@ public class RateLimitedPIDOutput implements PIDOutput {
double m;
double prev_rate = 0;
double prev_time = 0;
-
+
public RateLimitedPIDOutput(PIDOutput out, double maxChange) {
o = out;
m = maxChange;
}
-
+
public void pidWrite(double rate) {
double time = Timer.getFPGATimestamp();
double dTime = time-prev_time;
diff --git a/src/org/mckenzierobotics/lib/robot/RollingAvg.java b/src/org/mckenzierobotics/lib/robot/RollingAvg.java
index d73f64e..3001b8a 100644
--- a/src/org/mckenzierobotics/lib/robot/RollingAvg.java
+++ b/src/org/mckenzierobotics/lib/robot/RollingAvg.java
@@ -15,15 +15,15 @@
*
* THIS SOFTWARE IS PROVIDED BY FIRST AND CONTRIBUTORS``AS IS'' AND ANY
* EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
- * WARRANTIES OF MERCHANTABILITY NONINFRINGEMENT AND FITNESS FOR A PARTICULAR
- * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL FIRST OR CONTRIBUTORS BE LIABLE FOR
+ * WARRANTIES OF MERCHANTABILITY NONINFRINGEMENT AND FITNESS FOR A PARTICULAR
+ * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL FIRST OR CONTRIBUTORS BE LIABLE FOR
* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
- *
+ *
* @author Luke Shumaker <lukeshu@sbcglobal.net>
*/
@@ -71,7 +71,7 @@ public class RollingAvg implements PIDSource, PIDOutput {
else
return get();
}
-
+
public void pidWrite(double output) {
push(output);
}
diff --git a/src/org/mckenzierobotics/lib/robot/SendablePIDOutput.java b/src/org/mckenzierobotics/lib/robot/SendablePIDOutput.java
index 43852b1..679c6e1 100644
--- a/src/org/mckenzierobotics/lib/robot/SendablePIDOutput.java
+++ b/src/org/mckenzierobotics/lib/robot/SendablePIDOutput.java
@@ -5,7 +5,7 @@
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
- *
+ *
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
@@ -13,7 +13,7 @@
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
- *
+ *
* @author Luke Shumaker <lukeshu@sbcglobal.net>
*/
@@ -29,12 +29,12 @@ import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
public class SendablePIDOutput implements PIDOutput {
PIDOutput o;
String n;
-
+
public SendablePIDOutput(String name, PIDOutput out) {
n = name;
o = out;
}
-
+
public void pidWrite(double val) {
o.pidWrite(val);
SmartDashboard.putNumber(n, val);
diff --git a/src/org/usfirst/frc/team4272/robot2016/Autonomous.java b/src/org/usfirst/frc/team4272/robot2016/Autonomous.java
index 749e4cb..4fab67f 100644
--- a/src/org/usfirst/frc/team4272/robot2016/Autonomous.java
+++ b/src/org/usfirst/frc/team4272/robot2016/Autonomous.java
@@ -19,7 +19,7 @@ public class Autonomous {
c.rDrive = c.lDrive = 0.7;
//initially -0.7 to drive backwards
//0 to 9787 for going backwards
- //0 to negative for forward
+ //0 to negative for forward
//INDY: (15.5*140*1.1)
//PURDUE: (15.5*140*1.15) for a drop further
} else {
diff --git a/src/org/usfirst/frc/team4272/robot2016/HwRobot.java b/src/org/usfirst/frc/team4272/robot2016/HwRobot.java
index 27e64d8..9b3e4e1 100644
--- a/src/org/usfirst/frc/team4272/robot2016/HwRobot.java
+++ b/src/org/usfirst/frc/team4272/robot2016/HwRobot.java
@@ -22,13 +22,13 @@ public class HwRobot {
* - PWM: 0-9
* - PCM: 0-7 (the PCM is connected via CAN).
* - CAN
- *
+ *
* For completeness, the roboRIO also has: i2c, RS-232, SPI,
* RSL, 2xUSB-A, an accelerometer, and an expansion port.
*
* And, for communication: USB-B and Ethernet.
*/
-
+
public Encoder lDriveE = new Encoder(/*DIO*/2,/*DIO*/3);
private PIDOutput lDriveM = new PIDOutputSplitter(new Talon(/*PWM*/0),
new Talon(/*PWM*/1));
diff --git a/src/org/usfirst/frc/team4272/robot2016/Teleop.java b/src/org/usfirst/frc/team4272/robot2016/Teleop.java
index 4bc1b46..be88308 100644
--- a/src/org/usfirst/frc/team4272/robot2016/Teleop.java
+++ b/src/org/usfirst/frc/team4272/robot2016/Teleop.java
@@ -50,7 +50,7 @@ public class Teleop {
control.grab = grabButton.update(oi.xbox.getButton(Button.A));
control.push = pushButton.update(oi.xbox.getButton(Button.B));
-
+
if (camButton.update(oi.xbox.getButton(Button.RT))) {
try {
ProcessBuilder pb = new ProcessBuilder("/home/lvuser/tweeterbot/bin/snapPhoto");
diff --git a/src/org/usfirst/frc/team4272/robotlib/DoubleSolenoid.java b/src/org/usfirst/frc/team4272/robotlib/DoubleSolenoid.java
index 8698277..33524f1 100644
--- a/src/org/usfirst/frc/team4272/robotlib/DoubleSolenoid.java
+++ b/src/org/usfirst/frc/team4272/robotlib/DoubleSolenoid.java
@@ -3,7 +3,7 @@ package org.usfirst.frc.team4272.robotlib;
public class DoubleSolenoid extends edu.wpi.first.wpilibj.DoubleSolenoid {
private boolean enabled = true;
private Value value;
-
+
public DoubleSolenoid(int forwardChannel, int reverseChannel) {
super(forwardChannel, reverseChannel);
value = get();
@@ -12,7 +12,7 @@ public class DoubleSolenoid extends edu.wpi.first.wpilibj.DoubleSolenoid {
super(moduleNumber, forwardChannel, reverseChannel);
value = get();
}
-
+
public void setEnabled(boolean enabled) {
this.enabled = enabled;
if (enabled) {
@@ -21,15 +21,15 @@ public class DoubleSolenoid extends edu.wpi.first.wpilibj.DoubleSolenoid {
set(Value.kOff);
}
}
-
+
public void setForward(boolean forward) {
set(forward ? Value.kForward : Value.kReverse);
}
-
+
public boolean getForward() {
return value == Value.kForward;
}
-
+
public void set(Value value) {
this.value = value;
if (enabled) {
diff --git a/src/org/usfirst/frc/team4272/robotlib/LimitSwitchedPIDOutput.java b/src/org/usfirst/frc/team4272/robotlib/LimitSwitchedPIDOutput.java
index aa3aeaf..695d418 100644
--- a/src/org/usfirst/frc/team4272/robotlib/LimitSwitchedPIDOutput.java
+++ b/src/org/usfirst/frc/team4272/robotlib/LimitSwitchedPIDOutput.java
@@ -9,7 +9,7 @@ public class LimitSwitchedPIDOutput implements PIDOutput {
private final DigitalInput bakward;
private final boolean for_pressed;
private final boolean bak_pressed;
-
+
public LimitSwitchedPIDOutput(PIDOutput out,
DigitalInput forward, boolean for_pressed,
DigitalInput backward, boolean back_pressed) {
@@ -19,11 +19,11 @@ public class LimitSwitchedPIDOutput implements PIDOutput {
this.for_pressed = for_pressed;
this.bak_pressed = back_pressed;
}
-
+
public LimitSwitchedPIDOutput(PIDOutput out, DigitalInput forward, DigitalInput backward) {
this(out, forward, true, backward, true);
}
-
+
public void pidWrite(double v) {
if (forward.get() == for_pressed) { v = Math.min(v, 0); }
if (bakward.get() == bak_pressed) { v = Math.max(v, 0); }
diff --git a/src/org/usfirst/frc/team4272/robotlib/Xbox360Controller.java b/src/org/usfirst/frc/team4272/robotlib/Xbox360Controller.java
index d04fa23..0a4df83 100644
--- a/src/org/usfirst/frc/team4272/robotlib/Xbox360Controller.java
+++ b/src/org/usfirst/frc/team4272/robotlib/Xbox360Controller.java
@@ -56,7 +56,7 @@ public class Xbox360Controller extends Joystick {
}
/* Core functions *******************************************/
-
+
/**
* Get the value of an axis base on an enumerated type.
*
@@ -77,7 +77,7 @@ public class Xbox360Controller extends Joystick {
return getRawButton(button.id);
}
-
+
/* The actual code is done. The rest is boilerplate. See,
* this is why Java is terrible. Just 30% of the file
* actually doing useful stuff, the rest just filling
@@ -153,7 +153,7 @@ public class Xbox360Controller extends Joystick {
return getButton(Button.RB);
return false;
}
-
+
/**
* Get the state of a trigger; whether it is more than
* half-way pressed or not.
@@ -210,7 +210,7 @@ public class Xbox360Controller extends Joystick {
return Math.toDegrees(getDirectionRadians(Hand.kRight));
}
-
+
/* Unused wrappers for GenericHID/Joystick ******************/
/**
@@ -230,7 +230,7 @@ public class Xbox360Controller extends Joystick {
public double getThrottle() {
return 0.0;
}
-
+
/**
* This method is only here to complete the Joystick interface.
*