Saved
authorRohan Rodrigues <rohanrodrigues19@gmail.com>
Thu, 23 Mar 2017 17:36:59 +0000 (10:36 -0700)
committerRohan Rodrigues <rohanrodrigues19@gmail.com>
Thu, 23 Mar 2017 17:36:59 +0000 (10:36 -0700)
src/org/usfirst/frc/team3501/robot/Constants.java
src/org/usfirst/frc/team3501/robot/OI.java
src/org/usfirst/frc/team3501/robot/commands/climber/RunWinchContinuous.java
src/org/usfirst/frc/team3501/robot/commands/climber/ToggleWinch.java
src/org/usfirst/frc/team3501/robot/commands/driving/JoystickDrive.java
src/org/usfirst/frc/team3501/robot/commands/driving/ShiftDriveHighGear.java [new file with mode: 0644]
src/org/usfirst/frc/team3501/robot/commands/driving/ShiftDriveLowGear.java [new file with mode: 0644]
src/org/usfirst/frc/team3501/robot/subsystems/Climber.java

index 07b2028681b183e1b44bce9a80e5d9b4ccc7a5b5..48ec24277868d24a36b446c1d4b91f41a72d4bb0 100644 (file)
@@ -10,21 +10,28 @@ import edu.wpi.first.wpilibj.SPI;
  * constants for subsystems such as max and min values.
  */
 
  * constants for subsystems such as max and min values.
  */
 
+// have two buttons: one for shifting to high gear and the other for shifting to
+// low gear
+
 public class Constants {
   public static class OI {
 public class Constants {
   public static class OI {
-    public final static int LEFT_STICK_PORT = 0;
-    public final static int RIGHT_STICK_PORT = 1;
+    public final static int XBOX_CONTROLLER_PORT = 0;
+    // public final static int RIGHT_STICK_PORT = 1;
     public static final int GAME_PAD_PORT = 2;
 
     public static final int GAME_PAD_PORT = 2;
 
-    public final static int TOGGLE_GEAR_PORT = 5;
-    public final static int RUN_INTAKE_PORT = 1;
-    public final static int REVERSE_INTAKE_PORT = 2;
-
-    public final static int RUN_INDEXWHEEL_PORT = 1;
-    public final static int REVERSE_INDEXWHEEL_PORT = 2;
-    public static final int BRAKE_CANTALONS_PORT = 5;
-    public static final int COAST_CANTALONS_PORT = 6;
-
+    // Xbox Controller Ports
+    // public final static int TOGGLE_GEAR_PORT = 5;
+    public final static int SHIFT_LOW_PORT = 9;
+    public final static int SHIFT_HIGH_PORT = 10;
+    public final static int RUN_INTAKE_PORT = 6;
+    public final static int REVERSE_INTAKE_PORT = 8;
+    public final static int RUN_INDEXWHEEL_PORT = 5;
+    public final static int REVERSE_INDEXWHEEL_PORT = 7;
+    public static final int BRAKE_CANTALONS_PORT = 1;
+    public static final int COAST_CANTALONS_PORT = 3;
+    public static final int CLIMB_PORT = 4;
+
+    // Game Pad Ports
     public final static int TOGGLE_FLYWHEEL_PORT = 1;
     public static final int REVERSE_FLYWHEEL_PORT = 3;
     public static final int INCREASE_SHOOTER_SPEED_PORT = 8;
     public final static int TOGGLE_FLYWHEEL_PORT = 1;
     public static final int REVERSE_FLYWHEEL_PORT = 3;
     public static final int INCREASE_SHOOTER_SPEED_PORT = 8;
@@ -32,7 +39,6 @@ public class Constants {
     public static final int RESET_SHOOTER_SPEED_PORT = 5;
     public static final int TOGGLE_GEAR_MANIPULATOR_PORT = 2;
 
     public static final int RESET_SHOOTER_SPEED_PORT = 5;
     public static final int TOGGLE_GEAR_MANIPULATOR_PORT = 2;
 
-    public static final int CLIMB_PORT = 0;
   }
 
   public static class Shooter {
   }
 
   public static class Shooter {
index 7002a58bf1e4cbaeef433d5bd560c78543da1e60..c53369e412f984aa155687c56f1fa6244787d006 100644 (file)
@@ -3,7 +3,8 @@ package org.usfirst.frc.team3501.robot;
 import org.usfirst.frc.team3501.robot.commands.climber.BrakeCANTalons;
 import org.usfirst.frc.team3501.robot.commands.climber.CoastCANTalons;
 import org.usfirst.frc.team3501.robot.commands.climber.ToggleWinch;
 import org.usfirst.frc.team3501.robot.commands.climber.BrakeCANTalons;
 import org.usfirst.frc.team3501.robot.commands.climber.CoastCANTalons;
 import org.usfirst.frc.team3501.robot.commands.climber.ToggleWinch;
-import org.usfirst.frc.team3501.robot.commands.driving.ToggleDriveGear;
+import org.usfirst.frc.team3501.robot.commands.driving.ShiftDriveHighGear;
+import org.usfirst.frc.team3501.robot.commands.driving.ShiftDriveLowGear;
 import org.usfirst.frc.team3501.robot.commands.driving.ToggleGearManipulatorPiston;
 import org.usfirst.frc.team3501.robot.commands.intake.ReverseIntakeContinuous;
 import org.usfirst.frc.team3501.robot.commands.intake.RunIntakeContinuous;
 import org.usfirst.frc.team3501.robot.commands.driving.ToggleGearManipulatorPiston;
 import org.usfirst.frc.team3501.robot.commands.intake.ReverseIntakeContinuous;
 import org.usfirst.frc.team3501.robot.commands.intake.RunIntakeContinuous;
@@ -21,8 +22,8 @@ import edu.wpi.first.wpilibj.buttons.JoystickButton;
 
 public class OI {
   private static OI oi;
 
 public class OI {
   private static OI oi;
-  public static Joystick leftJoystick;
-  public static Joystick rightJoystick;
+  public static Joystick xboxController;
+  // public static Joystick rightJoystick;
   public static Joystick gamePad;
 
   public static Button runIndexWheel;
   public static Joystick gamePad;
 
   public static Button runIndexWheel;
@@ -30,7 +31,10 @@ public class OI {
   public static Button toggleFlyWheel;
   public static Button reverseFlyWheel;
 
   public static Button toggleFlyWheel;
   public static Button reverseFlyWheel;
 
-  public static Button toggleGear;
+  // public static Button toggleGear;
+  public static Button shiftHigh;
+  public static Button shiftLow;
+
   public static Button toggleGearManipulatorPiston;
 
   public static Button runIntake;
   public static Button toggleGearManipulatorPiston;
 
   public static Button runIntake;
@@ -45,15 +49,15 @@ public class OI {
   public static Button climb;
 
   public OI() {
   public static Button climb;
 
   public OI() {
-    leftJoystick = new Joystick(Constants.OI.LEFT_STICK_PORT);
-    rightJoystick = new Joystick(Constants.OI.RIGHT_STICK_PORT);
+    xboxController = new Joystick(Constants.OI.XBOX_CONTROLLER_PORT);
+    // rightJoystick = new Joystick(Constants.OI.RIGHT_STICK_PORT);
     gamePad = new Joystick(Constants.OI.GAME_PAD_PORT);
 
     gamePad = new Joystick(Constants.OI.GAME_PAD_PORT);
 
-    runIndexWheel = new JoystickButton(rightJoystick,
+    runIndexWheel = new JoystickButton(xboxController,
         Constants.OI.RUN_INDEXWHEEL_PORT);
     runIndexWheel.whileHeld(new RunIndexWheelContinuous());
 
         Constants.OI.RUN_INDEXWHEEL_PORT);
     runIndexWheel.whileHeld(new RunIndexWheelContinuous());
 
-    reverseIndexWheel = new JoystickButton(rightJoystick,
+    reverseIndexWheel = new JoystickButton(xboxController,
         Constants.OI.REVERSE_INDEXWHEEL_PORT);
     reverseIndexWheel.whileHeld(new ReverseIndexWheelContinuous());
 
         Constants.OI.REVERSE_INDEXWHEEL_PORT);
     reverseIndexWheel.whileHeld(new ReverseIndexWheelContinuous());
 
@@ -65,18 +69,26 @@ public class OI {
         Constants.OI.REVERSE_FLYWHEEL_PORT);
     reverseFlyWheel.whileHeld(new ReverseFlyWheelContinuous());
 
         Constants.OI.REVERSE_FLYWHEEL_PORT);
     reverseFlyWheel.whileHeld(new ReverseFlyWheelContinuous());
 
-    toggleGear = new JoystickButton(leftJoystick,
-        Constants.OI.TOGGLE_GEAR_PORT);
-    toggleGear.whenPressed(new ToggleDriveGear());
+    // toggleGear = new JoystickButton(xboxController,
+    // Constants.OI.TOGGLE_GEAR_PORT);
+    // toggleGear.whenPressed(new ToggleDriveGear());
+
+    shiftHigh = new JoystickButton(xboxController,
+        Constants.OI.SHIFT_HIGH_PORT);
+    shiftHigh.whenPressed(new ShiftDriveHighGear());
+
+    shiftLow = new JoystickButton(xboxController, Constants.OI.SHIFT_LOW_PORT);
+    shiftLow.whenPressed(new ShiftDriveLowGear());
 
     toggleGearManipulatorPiston = new JoystickButton(gamePad,
         Constants.OI.TOGGLE_GEAR_MANIPULATOR_PORT);
     toggleGearManipulatorPiston.whenPressed(new ToggleGearManipulatorPiston());
 
 
     toggleGearManipulatorPiston = new JoystickButton(gamePad,
         Constants.OI.TOGGLE_GEAR_MANIPULATOR_PORT);
     toggleGearManipulatorPiston.whenPressed(new ToggleGearManipulatorPiston());
 
-    runIntake = new JoystickButton(leftJoystick, Constants.OI.RUN_INTAKE_PORT);
+    runIntake = new JoystickButton(xboxController,
+        Constants.OI.RUN_INTAKE_PORT);
     runIntake.whileHeld(new RunIntakeContinuous());
 
     runIntake.whileHeld(new RunIntakeContinuous());
 
-    reverseIntake = new JoystickButton(leftJoystick,
+    reverseIntake = new JoystickButton(xboxController,
         Constants.OI.REVERSE_INTAKE_PORT);
     reverseIntake.whileHeld(new ReverseIntakeContinuous());
 
         Constants.OI.REVERSE_INTAKE_PORT);
     reverseIntake.whileHeld(new ReverseIntakeContinuous());
 
@@ -92,15 +104,15 @@ public class OI {
         Constants.OI.RESET_SHOOTER_SPEED_PORT);
     resetShooterSpeed.whenPressed(new ResetShootingSpeed());
 
         Constants.OI.RESET_SHOOTER_SPEED_PORT);
     resetShooterSpeed.whenPressed(new ResetShootingSpeed());
 
-    brakeCANTalons = new JoystickButton(rightJoystick,
+    brakeCANTalons = new JoystickButton(xboxController,
         Constants.OI.BRAKE_CANTALONS_PORT);
     brakeCANTalons.whenPressed(new BrakeCANTalons());
 
         Constants.OI.BRAKE_CANTALONS_PORT);
     brakeCANTalons.whenPressed(new BrakeCANTalons());
 
-    coastCANTalons = new JoystickButton(rightJoystick,
+    coastCANTalons = new JoystickButton(xboxController,
         Constants.OI.COAST_CANTALONS_PORT);
     coastCANTalons.whenPressed(new CoastCANTalons());
 
         Constants.OI.COAST_CANTALONS_PORT);
     coastCANTalons.whenPressed(new CoastCANTalons());
 
-    climb = new JoystickButton(leftJoystick, Constants.OI.CLIMB_PORT);
+    climb = new JoystickButton(xboxController, Constants.OI.CLIMB_PORT);
     climb.whenPressed(new ToggleWinch());
   }
 
     climb.whenPressed(new ToggleWinch());
   }
 
index 06fa1547db2131986d6ea88af5fba47ca3c1387c..664b201643b113a16b7944a1223d541b3bcb5ee3 100644 (file)
@@ -39,7 +39,7 @@ public class RunWinchContinuous extends Command {
 
   @Override
   protected void execute() {
 
   @Override
   protected void execute() {
-    double thrust = OI.leftJoystick.getY();
+    double thrust = OI.xboxController.getY();
     climber.setMotorValues(-thrust);
   }
 
     climber.setMotorValues(-thrust);
   }
 
index 47e464c9f7b34ecdbd53e7e15948c9287abd9a47..918481c37e2377a76ba5b5c2bca1f8a159b02a07 100644 (file)
@@ -25,6 +25,9 @@ public class ToggleWinch extends Command {
       climber.setMotorValues(climbingSpeed);
     } else {
       climber.setCANTalonsBrakeMode(climber.BRAKE_MODE);
       climber.setMotorValues(climbingSpeed);
     } else {
       climber.setCANTalonsBrakeMode(climber.BRAKE_MODE);
+
+      /* Not sure if should have */
+      climber.stop();
       end();
     }
   }
       end();
     }
   }
index 9007a545fce287951f650cad98ffa08bf9bd3515..aa9bfafffe20b46aa0ac71a372d57feda8e4f5cb 100755 (executable)
@@ -3,6 +3,7 @@ package org.usfirst.frc.team3501.robot.commands.driving;
 import org.usfirst.frc.team3501.robot.OI;
 import org.usfirst.frc.team3501.robot.Robot;
 
 import org.usfirst.frc.team3501.robot.OI;
 import org.usfirst.frc.team3501.robot.Robot;
 
+import edu.wpi.first.wpilibj.Joystick.AxisType;
 import edu.wpi.first.wpilibj.command.Command;
 
 /**
 import edu.wpi.first.wpilibj.command.Command;
 
 /**
@@ -22,13 +23,15 @@ public class JoystickDrive extends Command {
 
   @Override
   protected void execute() {
 
   @Override
   protected void execute() {
-    // final double thrust = OI.rightJoystick.getY();
-    // final double twist = OI.rightJoystick.getTwist();
-    //
-    // Robot.getDriveTrain().joystickDrive(-thrust, -twist);
-    double left = OI.leftJoystick.getY();
-    double right = OI.rightJoystick.getY();
-    Robot.getDriveTrain().tankDrive(left, right);
+    final double thrust = OI.xboxController.getY();
+    final double twist = OI.xboxController.getAxis(AxisType.kZ);
+
+    Robot.getDriveTrain().joystickDrive(-thrust, -twist);
+
+    /*
+     * double left = OI.leftJoystick.getY(); double right =
+     * OI.rightJoystick.getY(); Robot.getDriveTrain().tankDrive(-left, -right);
+     */
   }
 
   @Override
   }
 
   @Override
diff --git a/src/org/usfirst/frc/team3501/robot/commands/driving/ShiftDriveHighGear.java b/src/org/usfirst/frc/team3501/robot/commands/driving/ShiftDriveHighGear.java
new file mode 100644 (file)
index 0000000..08323ed
--- /dev/null
@@ -0,0 +1,43 @@
+package org.usfirst.frc.team3501.robot.commands.driving;
+
+import org.usfirst.frc.team3501.robot.Robot;
+import org.usfirst.frc.team3501.robot.subsystems.DriveTrain;
+
+import edu.wpi.first.wpilibj.command.Command;
+
+/**
+ * This command shifts the gear to high
+ *
+ * Author: Rohan Rodrigues
+ */
+public class ShiftDriveHighGear extends Command {
+  DriveTrain driveTrain = Robot.getDriveTrain();
+
+  public ShiftDriveHighGear() {
+    requires(driveTrain);
+  }
+
+  @Override
+  protected void initialize() {
+
+  }
+
+  @Override
+  protected void execute() {
+    driveTrain.setHighGear();
+    System.out.println("Current Value is: " + driveTrain.getLeftMotorVal());
+  }
+
+  @Override
+  protected boolean isFinished() {
+    return true;
+  }
+
+  @Override
+  protected void end() {
+  }
+
+  @Override
+  protected void interrupted() {
+  }
+}
diff --git a/src/org/usfirst/frc/team3501/robot/commands/driving/ShiftDriveLowGear.java b/src/org/usfirst/frc/team3501/robot/commands/driving/ShiftDriveLowGear.java
new file mode 100644 (file)
index 0000000..fbc3e56
--- /dev/null
@@ -0,0 +1,43 @@
+package org.usfirst.frc.team3501.robot.commands.driving;
+
+import org.usfirst.frc.team3501.robot.Robot;
+import org.usfirst.frc.team3501.robot.subsystems.DriveTrain;
+
+import edu.wpi.first.wpilibj.command.Command;
+
+/**
+ * This command shifts the gear to high
+ *
+ * Author: Rohan Rodrigues
+ */
+public class ShiftDriveLowGear extends Command {
+  DriveTrain driveTrain = Robot.getDriveTrain();
+
+  public ShiftDriveLowGear() {
+    requires(driveTrain);
+  }
+
+  @Override
+  protected void initialize() {
+
+  }
+
+  @Override
+  protected void execute() {
+    driveTrain.setLowGear();
+    System.out.println("Current Value is: " + driveTrain.getLeftMotorVal());
+  }
+
+  @Override
+  protected boolean isFinished() {
+    return true;
+  }
+
+  @Override
+  protected void end() {
+  }
+
+  @Override
+  protected void interrupted() {
+  }
+}
index d9268cb8f2705e921549d3f12abd2602dd51ad80..4cec792e1e937aa37e91282823c99e730369894c 100644 (file)
@@ -14,7 +14,7 @@ public class Climber extends Subsystem {
   public static final boolean COAST_MODE = false;
 
   public static final double CLIMBER_SPEED = 1.0;
   public static final boolean COAST_MODE = false;
 
   public static final double CLIMBER_SPEED = 1.0;
-  public boolean shouldBeClimbing = false;
+  public boolean shouldBeClimbing = true;
 
   private CANTalon winch;
 
 
   private CANTalon winch;