competition fixes cindy/competition
authorCindy Zhang <cindyzyx9@gmail.com>
Thu, 16 Mar 2017 23:46:42 +0000 (16:46 -0700)
committerCindy Zhang <cindyzyx9@gmail.com>
Thu, 16 Mar 2017 23:46:42 +0000 (16:46 -0700)
17 files changed:
src/org/usfirst/frc/team3501/robot/Constants.java
src/org/usfirst/frc/team3501/robot/MathLib.java
src/org/usfirst/frc/team3501/robot/OI.java
src/org/usfirst/frc/team3501/robot/Robot.java
src/org/usfirst/frc/team3501/robot/commands/climber/BrakeCANTalons.java [new file with mode: 0644]
src/org/usfirst/frc/team3501/robot/commands/climber/CoastCANTalons.java [new file with mode: 0644]
src/org/usfirst/frc/team3501/robot/commands/climber/MaintainClimbedPosition.java [deleted file]
src/org/usfirst/frc/team3501/robot/commands/climber/RunWinch.java
src/org/usfirst/frc/team3501/robot/commands/climber/RunWinchContinuous.java
src/org/usfirst/frc/team3501/robot/commands/climber/StopWinch.java
src/org/usfirst/frc/team3501/robot/commands/climber/ToggleWinch.java [deleted file]
src/org/usfirst/frc/team3501/robot/commands/driving/BrakeCANTalons.java [deleted file]
src/org/usfirst/frc/team3501/robot/commands/driving/CoastCANTalons.java [deleted file]
src/org/usfirst/frc/team3501/robot/commands/driving/ToggleDriveGear.java
src/org/usfirst/frc/team3501/robot/subsystems/Climber.java [new file with mode: 0644]
src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java
src/org/usfirst/frc/team3501/robot/subsystems/Shooter.java

index 4efaf21ef7c46e5a50ef41f985f5bf436ad4597d..840c49794dbd156ebaf131a24d9a2174a0e886aa 100644 (file)
@@ -46,9 +46,10 @@ public class Constants {
     public static final int PISTON_MODULE = 10;
     public static final int GEAR_MANIPULATOR_PISTON_FORWARD = 4,
         GEAR_MANIPULATOR_PISTON_REVERSE = 5;
-    public static final int LEFT_GEAR_PISTON_FORWARD = 1,
-        LEFT_GEAR_PISTON_REVERSE = 0, RIGHT_GEAR_PISTON_FORWARD = 3,
-        RIGHT_GEAR_PISTON_REVERSE = 2;
+
+    public static final int DRIVETRAIN_GEAR_FORWARD = 0,
+        DRIVETRAIN_GEAR_REVERSE = 1;
+
     public static final Value FORWARD_PISTON_VALUE = DoubleSolenoid.Value.kForward;
     public static final Value REVERSE_PISTON_VALUE = DoubleSolenoid.Value.kReverse;
 
@@ -69,7 +70,10 @@ public class Constants {
 
   public static class Intake {
     public static final int INTAKE_ROLLER_PORT = 8;
+  }
 
+  public static class Climber {
+    public static final int WINCH_PORT = 0;
   }
 
   public static enum Direction {
index 5269304da12d926bb211dd6d69f4050c2a74e30e..50cdd91d8376d6f905d4cf3b7be0368ae000d56f 100644 (file)
@@ -92,7 +92,7 @@ public class MathLib {
     }
   }
 
-  public static double limitValue(double val, double max, double min) {
+  public static double limitValue(double val, double min, double max) {
     if (val > max) {
       return max;
     } else if (val < min) {
index 61f39c3702c1d39331495e7d7ba73611d36d7b8f..e9c055248327cc7ca4bc57741eb93fe1c997072e 100644 (file)
@@ -1,7 +1,7 @@
 package org.usfirst.frc.team3501.robot;
 
-import org.usfirst.frc.team3501.robot.commands.driving.BrakeCANTalons;
-import org.usfirst.frc.team3501.robot.commands.driving.CoastCANTalons;
+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.driving.ToggleDriveGear;
 import org.usfirst.frc.team3501.robot.commands.driving.ToggleGearManipulatorPiston;
 import org.usfirst.frc.team3501.robot.commands.intake.ReverseIntakeContinuous;
index d551429f97cbf8b261c2b039e023230de5cd1368..8151cde6533837bd15907b3d37a795564a262e6e 100644 (file)
@@ -2,6 +2,8 @@ package org.usfirst.frc.team3501.robot;
 
 import org.usfirst.frc.team3501.robot.commandgroups.AutonMiddleGear;
 import org.usfirst.frc.team3501.robot.commandgroups.AutonSideGear;
+import org.usfirst.frc.team3501.robot.commands.driving.TimeDrive;
+import org.usfirst.frc.team3501.robot.subsystems.Climber;
 import org.usfirst.frc.team3501.robot.subsystems.DriveTrain;
 import org.usfirst.frc.team3501.robot.subsystems.Intake;
 import org.usfirst.frc.team3501.robot.subsystems.Shooter;
@@ -20,6 +22,7 @@ public class Robot extends IterativeRobot {
   private static Shooter shooter;
   private static OI oi;
   private static Intake intake;
+  private static Climber climber;
 
   Command autonCommand;
   SendableChooser autonChooser;
@@ -30,6 +33,7 @@ public class Robot extends IterativeRobot {
     oi = OI.getOI();
     shooter = Shooter.getShooter();
     intake = Intake.getIntake();
+    climber = Climber.getClimber();
 
     autonChooser = new SendableChooser();
     autonChooser.addDefault("Middle Gear", new AutonMiddleGear());
@@ -46,8 +50,6 @@ public class Robot extends IterativeRobot {
     CameraServer server = CameraServer.getInstance();
     UsbCamera climberCam = server.startAutomaticCapture("climbercam", 0);
     UsbCamera intakeCam = server.startAutomaticCapture("intakecam", 1);
-
-    driveTrain.setCANTalonsBrakeMode(driveTrain.DRIVE_COAST_MODE);
   }
 
   public static DriveTrain getDriveTrain() {
@@ -66,14 +68,17 @@ public class Robot extends IterativeRobot {
     return Intake.getIntake();
   }
 
+  public static Climber getClimber() {
+    return Climber.getClimber();
+  }
+
   @Override
   public void autonomousInit() {
-    // driveTrain.setLowGear();
-    driveTrain.setCANTalonsBrakeMode(driveTrain.DRIVE_COAST_MODE);
+    driveTrain.setLowGear();
 
     // autonCommand = (Command) autonChooser.getSelected();
-    // autonCommand = new TimeDrive(1.5, 0.6);
-    // Scheduler.getInstance().add(autonCommand);
+    autonCommand = new TimeDrive(2, 0.6);
+    Scheduler.getInstance().add(autonCommand);
   }
 
   @Override
@@ -83,8 +88,7 @@ public class Robot extends IterativeRobot {
 
   @Override
   public void teleopInit() {
-    // driveTrain.setHighGear();
-    driveTrain.setCANTalonsBrakeMode(driveTrain.DRIVE_COAST_MODE);
+    driveTrain.setHighGear();
   }
 
   @Override
diff --git a/src/org/usfirst/frc/team3501/robot/commands/climber/BrakeCANTalons.java b/src/org/usfirst/frc/team3501/robot/commands/climber/BrakeCANTalons.java
new file mode 100644 (file)
index 0000000..d0cfc34
--- /dev/null
@@ -0,0 +1,39 @@
+package org.usfirst.frc.team3501.robot.commands.climber;
+
+import org.usfirst.frc.team3501.robot.Robot;
+import org.usfirst.frc.team3501.robot.subsystems.Climber;
+
+import edu.wpi.first.wpilibj.command.Command;
+
+/**
+ *
+ */
+public class BrakeCANTalons extends Command {
+  Climber climber = Robot.getClimber();
+
+  public BrakeCANTalons() {
+    requires(climber);
+  }
+
+  @Override
+  protected void initialize() {
+    climber.setCANTalonsBrakeMode(climber.BRAKE_MODE);
+  }
+
+  @Override
+  protected void execute() {
+  }
+
+  @Override
+  protected boolean isFinished() {
+    return true;
+  }
+
+  @Override
+  protected void end() {
+  }
+
+  @Override
+  protected void interrupted() {
+  }
+}
diff --git a/src/org/usfirst/frc/team3501/robot/commands/climber/CoastCANTalons.java b/src/org/usfirst/frc/team3501/robot/commands/climber/CoastCANTalons.java
new file mode 100644 (file)
index 0000000..a2ecad2
--- /dev/null
@@ -0,0 +1,39 @@
+package org.usfirst.frc.team3501.robot.commands.climber;
+
+import org.usfirst.frc.team3501.robot.Robot;
+import org.usfirst.frc.team3501.robot.subsystems.Climber;
+
+import edu.wpi.first.wpilibj.command.Command;
+
+/**
+ *
+ */
+public class CoastCANTalons extends Command {
+  Climber climber = Robot.getClimber();
+
+  public CoastCANTalons() {
+    requires(climber);
+  }
+
+  @Override
+  protected void initialize() {
+    climber.setCANTalonsBrakeMode(climber.COAST_MODE);
+  }
+
+  @Override
+  protected void execute() {
+  }
+
+  @Override
+  protected boolean isFinished() {
+    return true;
+  }
+
+  @Override
+  protected void end() {
+  }
+
+  @Override
+  protected void interrupted() {
+  }
+}
diff --git a/src/org/usfirst/frc/team3501/robot/commands/climber/MaintainClimbedPosition.java b/src/org/usfirst/frc/team3501/robot/commands/climber/MaintainClimbedPosition.java
deleted file mode 100644 (file)
index 88ca8e0..0000000
+++ /dev/null
@@ -1,62 +0,0 @@
-package org.usfirst.frc.team3501.robot.commands.climber;
-
-import org.usfirst.frc.team3501.robot.Robot;
-import org.usfirst.frc.team3501.robot.subsystems.DriveTrain;
-
-import edu.wpi.first.wpilibj.command.Command;
-
-/**
- * This command runs the winch at a specified speed when the robot has completed
- * the climb and when the button triggering it is pressed. This command also
- * makes the drive train motors run because the winch is controlled by the drive
- * train.
- *
- * pre-condition: This command is run by a button in OI. The robot must have
- * completed climbing.
- *
- * post-condition: Winch motor set to a specified speed.
- *
- * @param motorVal
- *          value range is from -1 to 1
- *
- * @author shivanighanta
- *
- */
-public class MaintainClimbedPosition extends Command {
-
-  /**
-   * See JavaDoc comment in class for details
-   *
-   * @param time
-   *          time in seconds to run the winch
-   */
-  public MaintainClimbedPosition() {
-    requires(Robot.getDriveTrain());
-  }
-
-  @Override
-  protected void initialize() {
-  }
-
-  @Override
-  protected void execute() {
-    Robot.getDriveTrain().setMotorValues(DriveTrain.MAINTAIN_CLIMBED_POSITION,
-        DriveTrain.MAINTAIN_CLIMBED_POSITION);
-
-  }
-
-  @Override
-  protected boolean isFinished() {
-    return false;
-  }
-
-  @Override
-  protected void end() {
-    Robot.getDriveTrain().stop();
-  }
-
-  @Override
-  protected void interrupted() {
-    end();
-  }
-}
index 0e980a49e3b3bb02ed2db8a95d6f866d568f893f..5a76b5c182b377c6892b64c75572ca0857fa44ec 100644 (file)
@@ -1,6 +1,7 @@
 package org.usfirst.frc.team3501.robot.commands.climber;
 
 import org.usfirst.frc.team3501.robot.Robot;
+import org.usfirst.frc.team3501.robot.subsystems.Climber;
 
 import edu.wpi.first.wpilibj.command.Command;
 
@@ -23,6 +24,8 @@ import edu.wpi.first.wpilibj.command.Command;
  */
 
 public class RunWinch extends Command {
+  Climber climber = Robot.getClimber();
+
   private double time;
   private double motorVal;
 
@@ -35,7 +38,7 @@ public class RunWinch extends Command {
    *          value range is from -1 to 1
    */
   public RunWinch(double time, double motorVal) {
-    requires(Robot.getDriveTrain());
+    requires(climber);
     this.time = time;
     this.motorVal = motorVal;
   }
@@ -46,8 +49,7 @@ public class RunWinch extends Command {
 
   @Override
   protected void execute() {
-    Robot.getDriveTrain().setMotorValues(motorVal, motorVal);
-
+    climber.setMotorValues(motorVal);
   }
 
   @Override
@@ -57,7 +59,7 @@ public class RunWinch extends Command {
 
   @Override
   protected void end() {
-    Robot.getDriveTrain().stop();
+    climber.stop();
   }
 
   @Override
index 210199d86e2cb3dc178fb5d289f0446e4147368f..06fa1547db2131986d6ea88af5fba47ca3c1387c 100644 (file)
@@ -1,7 +1,8 @@
 package org.usfirst.frc.team3501.robot.commands.climber;
 
+import org.usfirst.frc.team3501.robot.OI;
 import org.usfirst.frc.team3501.robot.Robot;
-import org.usfirst.frc.team3501.robot.subsystems.DriveTrain;
+import org.usfirst.frc.team3501.robot.subsystems.Climber;
 
 import edu.wpi.first.wpilibj.command.Command;
 
@@ -18,7 +19,7 @@ import edu.wpi.first.wpilibj.command.Command;
  *
  */
 public class RunWinchContinuous extends Command {
-  DriveTrain driveTrain = Robot.getDriveTrain();
+  Climber climber = Robot.getClimber();
   private double climbingSpeed;
 
   /**
@@ -28,8 +29,8 @@ public class RunWinchContinuous extends Command {
    *          value range is from -1 to 1
    */
   public RunWinchContinuous() {
-    requires(driveTrain);
-    climbingSpeed = driveTrain.CLIMBER_SPEED;
+    requires(climber);
+    climbingSpeed = climber.CLIMBER_SPEED;
   }
 
   @Override
@@ -38,7 +39,8 @@ public class RunWinchContinuous extends Command {
 
   @Override
   protected void execute() {
-    Robot.getDriveTrain().setMotorValues(climbingSpeed, climbingSpeed);
+    double thrust = OI.leftJoystick.getY();
+    climber.setMotorValues(-thrust);
   }
 
   @Override
@@ -48,7 +50,7 @@ public class RunWinchContinuous extends Command {
 
   @Override
   protected void end() {
-
+    climber.stop();
   }
 
   @Override
index 597bd65d18ca44be30885d09d056aee9070f13af..0a2b5f97b7e2be8008c555461496eaa81cf7da6b 100644 (file)
@@ -1,6 +1,7 @@
 package org.usfirst.frc.team3501.robot.commands.climber;
 
 import org.usfirst.frc.team3501.robot.Robot;
+import org.usfirst.frc.team3501.robot.subsystems.Climber;
 
 import edu.wpi.first.wpilibj.command.Command;
 
@@ -11,9 +12,10 @@ import edu.wpi.first.wpilibj.command.Command;
  *
  */
 public class StopWinch extends Command {
+  Climber climber = Robot.getClimber();
 
   public StopWinch() {
-    requires(Robot.getDriveTrain());
+    requires(climber);
   }
 
   @Override
@@ -31,8 +33,7 @@ public class StopWinch extends Command {
 
   @Override
   protected void end() {
-    Robot.getDriveTrain().stop();
-
+    climber.stop();
   }
 
   @Override
diff --git a/src/org/usfirst/frc/team3501/robot/commands/climber/ToggleWinch.java b/src/org/usfirst/frc/team3501/robot/commands/climber/ToggleWinch.java
deleted file mode 100644 (file)
index 3e60406..0000000
+++ /dev/null
@@ -1,49 +0,0 @@
-package org.usfirst.frc.team3501.robot.commands.climber;
-
-import org.usfirst.frc.team3501.robot.Robot;
-import org.usfirst.frc.team3501.robot.subsystems.DriveTrain;
-
-import edu.wpi.first.wpilibj.command.Command;
-
-/**
- *
- */
-public class ToggleWinch extends Command {
-  DriveTrain driveTrain = Robot.getDriveTrain();
-  private double climbingSpeed;
-  private double maintainPositionSpeed;
-
-  public ToggleWinch() {
-    requires(driveTrain);
-    climbingSpeed = driveTrain.CLIMBER_SPEED;
-    maintainPositionSpeed = driveTrain.MAINTAIN_CLIMBED_POSITION;
-  }
-
-  @Override
-  protected void initialize() {
-  }
-
-  @Override
-  protected void execute() {
-    if (driveTrain.shouldBeClimbing) {
-      driveTrain.setMotorValues(climbingSpeed, climbingSpeed);
-    } else {
-      driveTrain.setMotorValues(maintainPositionSpeed, maintainPositionSpeed);
-    }
-  }
-
-  @Override
-  protected boolean isFinished() {
-    return false;
-  }
-
-  @Override
-  protected void end() {
-    driveTrain.shouldBeClimbing = !driveTrain.shouldBeClimbing;
-  }
-
-  @Override
-  protected void interrupted() {
-    end();
-  }
-}
diff --git a/src/org/usfirst/frc/team3501/robot/commands/driving/BrakeCANTalons.java b/src/org/usfirst/frc/team3501/robot/commands/driving/BrakeCANTalons.java
deleted file mode 100644 (file)
index 0a19e57..0000000
+++ /dev/null
@@ -1,39 +0,0 @@
-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;
-
-/**
- *
- */
-public class BrakeCANTalons extends Command {
-  private DriveTrain driveTrain = Robot.getDriveTrain();
-
-  public BrakeCANTalons() {
-    requires(driveTrain);
-  }
-
-  @Override
-  protected void initialize() {
-    driveTrain.setCANTalonsBrakeMode(driveTrain.DRIVE_BRAKE_MODE);
-  }
-
-  @Override
-  protected void execute() {
-  }
-
-  @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/CoastCANTalons.java b/src/org/usfirst/frc/team3501/robot/commands/driving/CoastCANTalons.java
deleted file mode 100644 (file)
index ea676f2..0000000
+++ /dev/null
@@ -1,39 +0,0 @@
-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;
-
-/**
- *
- */
-public class CoastCANTalons extends Command {
-  private DriveTrain driveTrain = Robot.getDriveTrain();
-
-  public CoastCANTalons() {
-    requires(driveTrain);
-  }
-
-  @Override
-  protected void initialize() {
-    driveTrain.setCANTalonsBrakeMode(driveTrain.DRIVE_COAST_MODE);
-  }
-
-  @Override
-  protected void execute() {
-  }
-
-  @Override
-  protected boolean isFinished() {
-    return true;
-  }
-
-  @Override
-  protected void end() {
-  }
-
-  @Override
-  protected void interrupted() {
-  }
-}
index e3c0dccac09eca69514a244f9a498ecd2a8b6223..281f3242c1b67df9533dfd59ff94524a7944c995 100644 (file)
@@ -28,11 +28,18 @@ public class ToggleDriveGear extends Command {
   @Override
   protected void execute() {
     Value rightPistonValue = driveTrain.getRightDriveTrainPiston();
+    System.out.println("I think i'm at " + rightPistonValue);
     if (rightPistonValue == Constants.DriveTrain.REVERSE_PISTON_VALUE) {
       driveTrain.setHighGear();
     } else {
       driveTrain.setLowGear();
     }
+    // boolean leftPistonValue = driveTrain.getLeftDriveTrainPiston();
+    // if (leftPistonValue == Constants.DriveTrain.RETRACT_VALUE) {
+    // driveTrain.setHighGear();
+    // } else {
+    // driveTrain.setLowGear();
+    // }
   }
 
   @Override
diff --git a/src/org/usfirst/frc/team3501/robot/subsystems/Climber.java b/src/org/usfirst/frc/team3501/robot/subsystems/Climber.java
new file mode 100644 (file)
index 0000000..4cb6c0b
--- /dev/null
@@ -0,0 +1,48 @@
+package org.usfirst.frc.team3501.robot.subsystems;
+
+import org.usfirst.frc.team3501.robot.Constants;
+import org.usfirst.frc.team3501.robot.MathLib;
+import org.usfirst.frc.team3501.robot.commands.climber.RunWinchContinuous;
+
+import com.ctre.CANTalon;
+
+import edu.wpi.first.wpilibj.command.Subsystem;
+
+public class Climber extends Subsystem {
+  public static Climber climber;
+
+  public static final boolean BRAKE_MODE = true;
+  public static final boolean COAST_MODE = false;
+
+  public static final double CLIMBER_SPEED = 0;
+
+  private CANTalon winch;
+
+  public Climber() {
+    winch = new CANTalon(Constants.Climber.WINCH_PORT);
+  }
+
+  public static Climber getClimber() {
+    if (climber == null) {
+      climber = new Climber();
+    }
+    return climber;
+  }
+
+  public void setMotorValues(double climbingSpeed) {
+    winch.set(MathLib.limitValue(climbingSpeed, 0.0, 1.0));
+  }
+
+  public void stop() {
+    winch.set(0);
+  }
+
+  public void setCANTalonsBrakeMode(boolean mode) {
+    winch.enableBrakeMode(mode);
+  }
+
+  @Override
+  protected void initDefaultCommand() {
+    setDefaultCommand(new RunWinchContinuous());
+  }
+}
index b7264f1c8bba799dfe8aa9f717e28564e28175ca..383abd6824cdd1129bcabd1c7a22156644cd9a90 100644 (file)
@@ -25,25 +25,17 @@ public class DriveTrain extends Subsystem {
   public static final double INCHES_PER_PULSE = WHEEL_DIAMETER * Math.PI
       / ENCODER_PULSES_PER_REVOLUTION;
 
-  public static final double MAINTAIN_CLIMBED_POSITION = 0;
-  public static final double TIME_TO_CLIMB_FOR = 0;
-  public static final double CLIMBER_SPEED = 0;
-
-  public static final boolean DRIVE_BRAKE_MODE = true;
-  public static final boolean DRIVE_COAST_MODE = false;
-
   private static DriveTrain driveTrain;
 
   private final CANTalon frontLeft, frontRight, rearLeft, rearRight;
   private final RobotDrive robotDrive;
   private final Encoder leftEncoder, rightEncoder;
-  private final DoubleSolenoid leftDriveTrainPiston, rightDriveTrainPiston;
+  private final DoubleSolenoid rightDriveTrainPiston;
+  // private final Solenoid leftDriveTrainPiston;
   private final DoubleSolenoid gearManipulatorPiston;
 
   private ADXRS450_Gyro imu;
 
-  public boolean shouldBeClimbing = false;
-
   private DriveTrain() {
     // MOTOR CONTROLLERS
     frontLeft = new CANTalon(Constants.DriveTrain.FRONT_LEFT);
@@ -66,14 +58,12 @@ public class DriveTrain extends Subsystem {
     this.imu = new ADXRS450_Gyro(Constants.DriveTrain.GYRO_PORT);
 
     // TODO: Not sure if MODULE_NUMBER should be the same for both
-    leftDriveTrainPiston = new DoubleSolenoid(
-        Constants.DriveTrain.PISTON_MODULE,
-        Constants.DriveTrain.LEFT_GEAR_PISTON_FORWARD,
-        Constants.DriveTrain.LEFT_GEAR_PISTON_REVERSE);
+    // leftDriveTrainPiston = new Solenoid(Constants.DriveTrain.PISTON_MODULE,
+    // Constants.DriveTrain.LEFT_GEAR_PISTON_PORT);
     rightDriveTrainPiston = new DoubleSolenoid(
         Constants.DriveTrain.PISTON_MODULE,
-        Constants.DriveTrain.RIGHT_GEAR_PISTON_FORWARD,
-        Constants.DriveTrain.RIGHT_GEAR_PISTON_REVERSE);
+        Constants.DriveTrain.DRIVETRAIN_GEAR_FORWARD,
+        Constants.DriveTrain.DRIVETRAIN_GEAR_REVERSE);
 
     gearManipulatorPiston = new DoubleSolenoid(
         Constants.DriveTrain.PISTON_MODULE,
@@ -169,9 +159,9 @@ public class DriveTrain extends Subsystem {
    * @return a value that is the current setpoint for the piston kReverse or
    * KForward
    */
-  public Value getLeftDriveTrainPiston() {
-    return leftDriveTrainPiston.get();
-  }
+  // public boolean getLeftDriveTrainPiston() {
+  // return leftDriveTrainPiston.get();
+  // }
 
   /*
    * @return a value that is the current setpoint for the piston kReverse or
@@ -199,8 +189,15 @@ public class DriveTrain extends Subsystem {
    * Changes the gear to a DoubleSolenoid.Value
    */
   private void changeGear(DoubleSolenoid.Value gear) {
-    leftDriveTrainPiston.set(gear);
+    System.out.println("shifting to " + gear);
     rightDriveTrainPiston.set(gear);
+    System.out.println("after: " + this.getRightDriveTrainPiston());
+
+    //
+    // if (gear == Constants.DriveTrain.FORWARD_PISTON_VALUE)
+    // leftDriveTrainPiston.set(Constants.DriveTrain.EXTEND_VALUE);
+    // else
+    // leftDriveTrainPiston.set(Constants.DriveTrain.RETRACT_VALUE);
   }
 
   public Value getGearManipulatorPistonValue() {
@@ -219,12 +216,4 @@ public class DriveTrain extends Subsystem {
   protected void initDefaultCommand() {
     setDefaultCommand(new JoystickDrive());
   }
-
-  public void setCANTalonsBrakeMode(boolean mode) {
-    frontLeft.enableBrakeMode(mode);
-    rearLeft.enableBrakeMode(mode);
-
-    frontRight.enableBrakeMode(mode);
-    rearRight.enableBrakeMode(mode);
-  }
 }
index ab36fddee10a8be135c5589ef4c1a8b5baa8d0e2..5711b2696ca632e6e790920f5a97057a2660f34b 100644 (file)
@@ -20,8 +20,8 @@ public class Shooter extends Subsystem {
   private static final double RPM_THRESHOLD = 10;
   private static final double DEFAULT_INDEXING_MOTOR_VALUE = 0.75;
   private static final double REVERSE_FLYWHEEL_MOTOR_VALUE = -0.75;
-  private static final double DEFAULT_SHOOTING_SPEED = 2700; // rpm
-  private static final double SHOOTING_SPEED_INCREMENT = 50;
+  private static final double DEFAULT_SHOOTING_SPEED = 2875; // rpm
+  private static final double SHOOTING_SPEED_INCREMENT = 25;
 
   private double targetShootingSpeed = DEFAULT_SHOOTING_SPEED;
   private double currentShooterMotorValue = 0;