misc cleanup
authorLogan Howard <logan@oflogan.com>
Sat, 18 Apr 2015 02:44:55 +0000 (19:44 -0700)
committerLogan Howard <logan@oflogan.com>
Sat, 18 Apr 2015 02:44:55 +0000 (19:44 -0700)
src/org/usfirst/frc/team3501/robot/OI.java
src/org/usfirst/frc/team3501/robot/RobotMap.java
src/org/usfirst/frc/team3501/robot/autons/PickUpContainer.java
src/org/usfirst/frc/team3501/robot/subsystems/Arm.java
src/org/usfirst/frc/team3501/robot/subsystems/Drivetrain.java

index 82c4217ab6229cc1dd87f966c5c72c2ed98ec013..1dc8e1ce52b3832a3a070c01b35b7c8de65ea4b3 100644 (file)
@@ -5,22 +5,21 @@ import java.util.Arrays;
 import org.usfirst.frc.team3501.robot.commands.*;
 
 public class OI {
+
     private Joystick left, right;
 
     public OI() {
         left  = new Joystick(RobotMap.LEFT_JOYSTICK_PORT);
         right = new Joystick(RobotMap.RIGHT_JOYSTICK_PORT);
 
-        right.whenPressed(1, new CloseClaw());
+        right.whenPressed(1,  new CloseClaw());
         right.whenReleased(1, new OpenClaw());
-
-        right.whenPressed(2, new ToggleClaw());
+        right.whenPressed(2,  new ToggleClaw());
 
         right.whenPressed(11, new TurnOffCompressor());
         right.whenPressed(12, new TurnOffCompressor());
-
-        right.whenPressed(7, new TurnOnCompressor());
-        right.whenPressed(8, new TurnOnCompressor());
+        right.whenPressed(7,  new TurnOnCompressor());
+        right.whenPressed(8,  new TurnOnCompressor());
 
         // potential bug point: this should "Just Work" because as soon as
         // command stops running, left stick pos at 0 should take over...
index 5e73c6589c89aed2c68501fdba08e96637d7bfd9..2f2da695e89ff53a3bf1e9b99f15ec86c6461e6b 100644 (file)
@@ -3,6 +3,7 @@ package org.usfirst.frc.team3501.robot;
 import edu.wpi.first.wpilibj.DoubleSolenoid.Value;
 
 public class RobotMap {
+
     // driver station
     public static final int LEFT_JOYSTICK_PORT = 0, RIGHT_JOYSTICK_PORT = 1;
 
@@ -15,18 +16,18 @@ public class RobotMap {
 
     public static final double MAX_DRIVE_SPEED = 0.7;
 
-    // claw
-    public static final int CLAW_FORWARD_CHANNEL = 0, CLAW_REVERSE_CHANNEL = 1;
-
-    public static final Value OPEN = Value.kForward, CLOSED = Value.kReverse;
-
     // arm
     public static final int LEFT_WINCH_ADDRESS = 2, RIGHT_WINCH_ADDRESS = 7;
 
     public static final double ARM_ADJUST_SPEED = 0.3;
 
+    // claw
+    public static final int CLAW_FORWARD_CHANNEL = 0, CLAW_REVERSE_CHANNEL = 1;
+
+    public static final Value OPEN = Value.kForward, CLOSED = Value.kReverse;
+
     // auton
     public static final double OVER_STEP_TIME = 1.2, OVER_STEP_SPEED = 0.7,
                                PAST_STEP_TIME = 1.5, PAST_STEP_SPEED = 0.5,
-                               PICKUP_TIME    = 1.4, PICKUP_SPEED = 0.5;
+                               PICKUP_TIME    = 1.4, PICKUP_SPEED    = 0.5;
 }
index 9b08d1fa57930dcfde17503097101d301dcd174f..b930f124f29cd954783657d395022fc7a2ee5674 100644 (file)
@@ -1,5 +1,6 @@
 package org.usfirst.frc.team3501.robot.autons;
 
+import org.usfirst.frc.team3501.robot.Robot;
 import org.usfirst.frc.team3501.robot.RobotMap;
 import org.usfirst.frc.team3501.robot.commands.*;
 
@@ -10,6 +11,9 @@ public class PickUpContainer extends CommandGroup {
     public PickUpContainer() {
         super("PickUpContainer");
 
+        requires(Robot.arm);
+        requires(Robot.claw);
+
         queueCommands();
     }
 
index f42de1dfa0670af331e3521b4d5574f4c53efdf5..eb11c8aebcd555df8904f8931adbd2b0d7e91c3b 100644 (file)
@@ -34,7 +34,7 @@ public class Arm extends Subsystem {
         left.set(0);
     }
 
-    public double getSpeedFromJoystick(double speed) {
+    private double getSpeedFromJoystick(double speed) {
         if (Math.abs(speed) < RobotMap.MIN_ARM_JOYSTICK_INPUT)
             speed = 0;
 
index 90e78473d6971732bbc741ad769e4ec8bdb12809..1267f2c914935d5e18c4787f6a353d2f80feb17f 100644 (file)
@@ -25,7 +25,7 @@ public class Drivetrain extends Subsystem {
     public void drive(double forward, double twist) {
         if (Math.abs(forward) < RobotMap.MIN_DRIVE_JOYSTICK_INPUT)
             forward = 0;
-        if (Math.abs(twist) < RobotMap.MIN_DRIVE_JOYSTICK_INPUT)
+        if (Math.abs(twist)   < RobotMap.MIN_DRIVE_JOYSTICK_INPUT)
             twist = 0;
 
         robotDrive.arcadeDrive(