competition fixes
authorCindy Zhang <cindyzyx9@gmail.com>
Sun, 12 Mar 2017 00:36:19 +0000 (16:36 -0800)
committerCindy Zhang <cindyzyx9@gmail.com>
Sun, 12 Mar 2017 00:36:19 +0000 (16:36 -0800)
src/org/usfirst/frc/team3501/robot/Constants.java
src/org/usfirst/frc/team3501/robot/OI.java
src/org/usfirst/frc/team3501/robot/Robot.java
src/org/usfirst/frc/team3501/robot/commandgroups/AutonMiddleGear.java
src/org/usfirst/frc/team3501/robot/commandgroups/AutonSideGear.java
src/org/usfirst/frc/team3501/robot/commands/driving/DriveDistance.java
src/org/usfirst/frc/team3501/robot/commands/driving/ToggleDriveGear.java
src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java
src/org/usfirst/frc/team3501/robot/subsystems/Shooter.java

index f0cc6e2a0f0286ed0aafe6ce1b3d845e0e68c7a9..4efaf21ef7c46e5a50ef41f985f5bf436ad4597d 100644 (file)
@@ -18,18 +18,19 @@ public class Constants {
 
     public final static int TOGGLE_GEAR_PORT = 5;
     public final static int RUN_INTAKE_PORT = 1;
-    public final static int REVERSE_INTAKE_PORT = 4;
+    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 = 3;
-
-    public final static int TOGGLE_FLYWHEEL_PORT = 4;
-    public static final int REVERSE_FLYWHEEL_PORT = 1;
-    public static final int INCREASE_SHOOTER_SPEED_PORT = 6;
-    public static final int DECREASE_SHOOTER_SPEED_PORT = 2;
-    public static final int TOGGLE_GEAR_MANIPULATOR_PORT = 3;
+    public static final int COAST_CANTALONS_PORT = 6;
+
+    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 static final int DECREASE_SHOOTER_SPEED_PORT = 7;
+    public static final int RESET_SHOOTER_SPEED_PORT = 5;
+    public static final int TOGGLE_GEAR_MANIPULATOR_PORT = 2;
   }
 
   public static class Shooter {
@@ -39,19 +40,14 @@ public class Constants {
     public static final int INDEX_WHEEL = 7;
 
     public final static int HALL_EFFECT_PORT = 9;
-
-    public static final int MODULE_NUMBER = 10, PISTON_FORWARD = 4,
-        PISTON_REVERSE = 5;
-    public static final Value HIGH_GEAR = DoubleSolenoid.Value.kForward;
-    public static final Value LOW_GEAR = DoubleSolenoid.Value.kReverse;
   }
 
   public static class DriveTrain {
     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 = 0,
-        LEFT_GEAR_PISTON_REVERSE = 1, RIGHT_GEAR_PISTON_FORWARD = 3,
+    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 Value FORWARD_PISTON_VALUE = DoubleSolenoid.Value.kForward;
     public static final Value REVERSE_PISTON_VALUE = DoubleSolenoid.Value.kReverse;
index 9f8ea7ae594b5d33d07fa18bcb79935745041915..61f39c3702c1d39331495e7d7ba73611d36d7b8f 100644 (file)
@@ -8,6 +8,7 @@ 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.shooter.DecreaseShootingSpeed;
 import org.usfirst.frc.team3501.robot.commands.shooter.IncreaseShootingSpeed;
+import org.usfirst.frc.team3501.robot.commands.shooter.ResetShootingSpeed;
 import org.usfirst.frc.team3501.robot.commands.shooter.ReverseFlyWheelContinuous;
 import org.usfirst.frc.team3501.robot.commands.shooter.ReverseIndexWheelContinuous;
 import org.usfirst.frc.team3501.robot.commands.shooter.RunFlyWheelContinuous;
@@ -36,6 +37,7 @@ public class OI {
 
   public static Button increaseShooterSpeed;
   public static Button decreaseShooterSpeed;
+  public static Button resetShooterSpeed;
 
   public static Button brakeCANTalons;
   public static Button coastCANTalons;
@@ -84,6 +86,10 @@ public class OI {
         Constants.OI.DECREASE_SHOOTER_SPEED_PORT);
     decreaseShooterSpeed.whenPressed(new DecreaseShootingSpeed());
 
+    resetShooterSpeed = new JoystickButton(gamePad,
+        Constants.OI.RESET_SHOOTER_SPEED_PORT);
+    resetShooterSpeed.whenPressed(new ResetShootingSpeed());
+
     brakeCANTalons = new JoystickButton(rightJoystick,
         Constants.OI.BRAKE_CANTALONS_PORT);
     brakeCANTalons.whenPressed(new BrakeCANTalons());
index a9fb3bf859cd9fd27cbdbdcc55ca9c7b87c52aaf..d551429f97cbf8b261c2b039e023230de5cd1368 100644 (file)
@@ -1,5 +1,7 @@
 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.subsystems.DriveTrain;
 import org.usfirst.frc.team3501.robot.subsystems.Intake;
 import org.usfirst.frc.team3501.robot.subsystems.Shooter;
@@ -8,7 +10,9 @@ import edu.wpi.cscore.UsbCamera;
 import edu.wpi.first.wpilibj.CameraServer;
 import edu.wpi.first.wpilibj.DriverStation;
 import edu.wpi.first.wpilibj.IterativeRobot;
+import edu.wpi.first.wpilibj.command.Command;
 import edu.wpi.first.wpilibj.command.Scheduler;
+import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
 import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
 
 public class Robot extends IterativeRobot {
@@ -17,6 +21,9 @@ public class Robot extends IterativeRobot {
   private static OI oi;
   private static Intake intake;
 
+  Command autonCommand;
+  SendableChooser autonChooser;
+
   @Override
   public void robotInit() {
     driveTrain = DriveTrain.getDriveTrain();
@@ -24,6 +31,18 @@ public class Robot extends IterativeRobot {
     shooter = Shooter.getShooter();
     intake = Intake.getIntake();
 
+    autonChooser = new SendableChooser();
+    autonChooser.addDefault("Middle Gear", new AutonMiddleGear());
+    autonChooser.addObject("Red Boiler Gear",
+        new AutonSideGear("RED", "BOILER"));
+    autonChooser.addObject("Red Retrieval Gear",
+        new AutonSideGear("RED", "RETRIEVAL"));
+    autonChooser.addObject("Blue Boiler Gear",
+        new AutonSideGear("BLUE", "BOILER"));
+    autonChooser.addObject("Blue Retrieval Gear",
+        new AutonSideGear("BLUE", "RETRIEVAL"));
+    SmartDashboard.putData("Autonomous Chooser", autonChooser);
+
     CameraServer server = CameraServer.getInstance();
     UsbCamera climberCam = server.startAutomaticCapture("climbercam", 0);
     UsbCamera intakeCam = server.startAutomaticCapture("intakecam", 1);
@@ -47,12 +66,14 @@ public class Robot extends IterativeRobot {
     return Intake.getIntake();
   }
 
-  // If the gear values do not match in the left and right piston, then they are
-  // both set to high gear
   @Override
   public void autonomousInit() {
-    driveTrain.setHighGear();
+    // driveTrain.setLowGear();
     driveTrain.setCANTalonsBrakeMode(driveTrain.DRIVE_COAST_MODE);
+
+    // autonCommand = (Command) autonChooser.getSelected();
+    // autonCommand = new TimeDrive(1.5, 0.6);
+    // Scheduler.getInstance().add(autonCommand);
   }
 
   @Override
@@ -62,26 +83,16 @@ public class Robot extends IterativeRobot {
 
   @Override
   public void teleopInit() {
+    // driveTrain.setHighGear();
     driveTrain.setCANTalonsBrakeMode(driveTrain.DRIVE_COAST_MODE);
   }
 
   @Override
   public void teleopPeriodic() {
-    driveTrain.printEncoderOutput();
     Scheduler.getInstance().run();
     updateSmartDashboard();
   }
 
-  @Override
-  public void disabledInit() {
-    driveTrain.setCANTalonsBrakeMode(driveTrain.DRIVE_BRAKE_MODE);
-  }
-  //
-  // @Override
-  // public void disabledPeriodic() {
-  // Scheduler.getInstance().add(new RunFlyWheel(2));
-  // }
-
   public void updateSmartDashboard() {
     SmartDashboard.putNumber("left encode ",
         driveTrain.getLeftEncoderDistance());
index 913bbd7e746c6b9b39d9dd4fc9be58a49b99564f..4880baf28f19e1c136521117d1114e49513c15c8 100644 (file)
@@ -1,12 +1,9 @@
 
 package org.usfirst.frc.team3501.robot.commandgroups;
 
-import org.usfirst.frc.team3501.robot.Constants.Direction;
 import org.usfirst.frc.team3501.robot.commands.driving.DriveDistance;
-import org.usfirst.frc.team3501.robot.commands.driving.TurnForAngle;
 
 import edu.wpi.first.wpilibj.command.CommandGroup;
-import edu.wpi.first.wpilibj.command.WaitCommand;
 
 /**
  *
@@ -36,20 +33,14 @@ public class AutonMiddleGear extends CommandGroup {
    *          direction to turn after placing gear on peg in order to cross the
    *          baseline. Only Direction.LEFT and Direction.RIGHT will be accepted
    */
-  public AutonMiddleGear(Direction direction) {
+  public AutonMiddleGear() {
     addSequential(new DriveDistance(DISTANCE_TO_PEG, maxTimeOut));
-    addSequential(new WaitCommand(3));
-    addSequential(new DriveDistance(DISTANCE_TO_BACK_OUT, maxTimeOut));
-    addSequential(new TurnForAngle(ANGLE_TO_TURN, direction, maxTimeOut));
-    addSequential(new DriveDistance(THIRD_DISTANCE_TO_TRAVEL, maxTimeOut));
-    addSequential(
-        new TurnForAngle(ANGLE_TO_TURN, oppositeOf(direction), maxTimeOut));
-    addSequential(new DriveDistance(DISTANCE_TO_BASELINE, maxTimeOut));
-  }
-
-  private Direction oppositeOf(Direction direction) {
-    if (direction == Direction.LEFT)
-      return Direction.RIGHT;
-    return Direction.LEFT;
+    // addSequential(new WaitCommand(3));
+    // addSequential(new DriveDistance(DISTANCE_TO_BACK_OUT, maxTimeOut));
+    // addSequential(new TurnForAngle(ANGLE_TO_TURN, direction, maxTimeOut));
+    // addSequential(new DriveDistance(THIRD_DISTANCE_TO_TRAVEL, maxTimeOut));
+    // addSequential(
+    // new TurnForAngle(ANGLE_TO_TURN, oppositeOf(direction), maxTimeOut));
+    // addSequential(new DriveDistance(DISTANCE_TO_BASELINE, maxTimeOut));
   }
 }
index 386dfe598711dc7a2c8456e9cb869f80ea3035bb..70f7226857e3ef835dbdc1396ee8f4c7de3d8959 100644 (file)
@@ -34,7 +34,7 @@ public class AutonSideGear extends CommandGroup {
    * inches and 205.7286 inches from the right side of the arena this program
    * chooses which peg to go for based on the starting point
    */
-  public AutonSideGear(String side) {
+  public AutonSideGear(String team, String side) {
     requires(Robot.getDriveTrain());
 
     if (side.equals("BOILER")) {
@@ -42,7 +42,12 @@ public class AutonSideGear extends CommandGroup {
           131.6 - (94.88 - ROBOT_WIDTH / 2 - distanceFromCorner) / Math.sqrt(3)
               - ROBOT_LENGTH / 2,
           5));
-      addSequential(new TurnForAngle(60, Direction.RIGHT, 5));
+
+      if (team.equals("RED"))
+        addSequential(new TurnForAngle(60, Direction.LEFT, 5));
+      else if (team.equals("BLUE"))
+        addSequential(new TurnForAngle(60, Direction.RIGHT, 5));
+
       addSequential(new DriveDistance(
           2 * (94.88 - ROBOT_WIDTH / 2 - distanceFromCorner) / Math.sqrt(3)
               - ROBOT_LENGTH / 2 + 7,
@@ -52,7 +57,12 @@ public class AutonSideGear extends CommandGroup {
           131.6 - (93.13 - ROBOT_WIDTH / 2 - distanceFromCorner) / Math.sqrt(3)
               - ROBOT_LENGTH / 2,
           5));
-      addSequential(new TurnForAngle(60, Direction.LEFT, 5));
+
+      if (team.equals("RED"))
+        addSequential(new TurnForAngle(60, Direction.RIGHT, 5));
+      else if (team.equals("BLUE"))
+        addSequential(new TurnForAngle(60, Direction.LEFT, 5));
+
       addSequential(new DriveDistance(
           2 * (93.13 - ROBOT_WIDTH / 2 - distanceFromCorner) / Math.sqrt(3)
               - ROBOT_LENGTH / 2,
index 582cd80b69abb799a89a7b3afdcd56432d22a738..7b721e0a46dd1a6bba47e1cdf9dda7e9447e6e08 100755 (executable)
@@ -52,7 +52,7 @@ public class DriveDistance extends Command {
   @Override
   protected void execute() {
     double xVal = gyroP * (driveTrain.getAngle() - zeroAngle);
-    double yVal = driveController.calcPID(driveTrain.getAvgEncoderDistance());
+    double yVal = driveController.calcPID(driveTrain.getRightEncoderDistance());
 
     double leftDrive = yVal - xVal;
     double rightDrive = yVal + xVal;
index ee15ec8a5415c7dcc68b952649edf7600e93b060..e3c0dccac09eca69514a244f9a498ecd2a8b6223 100644 (file)
@@ -27,9 +27,8 @@ public class ToggleDriveGear extends Command {
 
   @Override
   protected void execute() {
-    Value leftPistonValue = driveTrain.getLeftDriveTrainPiston();
     Value rightPistonValue = driveTrain.getRightDriveTrainPiston();
-    if (leftPistonValue == Constants.DriveTrain.REVERSE_PISTON_VALUE) {
+    if (rightPistonValue == Constants.DriveTrain.REVERSE_PISTON_VALUE) {
       driveTrain.setHighGear();
     } else {
       driveTrain.setLowGear();
index a6a6f8c9ce7e7c7e434e144dcd316a3e3d35e8d9..b7264f1c8bba799dfe8aa9f717e28564e28175ca 100644 (file)
@@ -14,7 +14,7 @@ import edu.wpi.first.wpilibj.RobotDrive;
 import edu.wpi.first.wpilibj.command.Subsystem;
 
 public class DriveTrain extends Subsystem {
-  public static double driveP = 0.012, driveI = 0.0011, driveD = -0.002;
+  public static double driveP = 0.01, driveI = 0.00115, driveD = -0.002;
   public static double smallTurnP = 0.004, smallTurnI = 0.0013,
       smallTurnD = 0.005;
   public static double largeTurnP = .003, largeTurnI = .0012, largeTurnD = .006;
@@ -101,7 +101,10 @@ public class DriveTrain extends Subsystem {
   }
 
   public void joystickDrive(final double thrust, final double twist) {
-    robotDrive.arcadeDrive(thrust, twist, true);
+    if ((thrust < 0.1 && thrust > -0.1) && (twist < 0.1 && twist > -0.1))
+      robotDrive.arcadeDrive(0, 0, true);
+    else
+      robotDrive.arcadeDrive(thrust, twist, true);
   }
 
   public void stop() {
index 85ecf468d6a2498a420813de8a41e84105c8c0ce..ab36fddee10a8be135c5589ef4c1a8b5baa8d0e2 100644 (file)
@@ -7,8 +7,6 @@ import org.usfirst.frc.team3501.robot.utils.PIDController;
 
 import com.ctre.CANTalon;
 
-import edu.wpi.first.wpilibj.DoubleSolenoid;
-import edu.wpi.first.wpilibj.DoubleSolenoid.Value;
 import edu.wpi.first.wpilibj.command.Subsystem;
 
 public class Shooter extends Subsystem {
@@ -28,17 +26,12 @@ public class Shooter extends Subsystem {
   private double targetShootingSpeed = DEFAULT_SHOOTING_SPEED;
   private double currentShooterMotorValue = 0;
 
-  private final DoubleSolenoid piston;
-
   private Shooter() {
     flyWheel1 = new CANTalon(Constants.Shooter.FLY_WHEEL1);
     flyWheel2 = new CANTalon(Constants.Shooter.FLY_WHEEL2);
     indexWheel = new CANTalon(Constants.Shooter.INDEX_WHEEL);
 
     hallEffect = new HallEffectSensor(Constants.Shooter.HALL_EFFECT_PORT, 1);
-
-    piston = new DoubleSolenoid(Constants.Shooter.MODULE_NUMBER,
-        Constants.Shooter.PISTON_FORWARD, Constants.Shooter.PISTON_REVERSE);
   }
 
   /**
@@ -60,7 +53,7 @@ public class Shooter extends Subsystem {
    *          motor value from -1 to 1(fastest forward)
    */
   public void setFlyWheelMotorVal(double val) {
-    val = MathLib.restrictToRange(val, 0.0, 1.0);
+    val = MathLib.restrictToRange(val, -1.0, 1.0);
     flyWheel1.set(val);
     flyWheel2.set(val);
   }
@@ -149,22 +142,6 @@ public class Shooter extends Subsystem {
     this.currentShooterMotorValue = 0;
   }
 
-  public Value getPistonValue() {
-    return piston.get();
-  }
-
-  public void setHighGear() {
-    changeGear(Constants.Shooter.HIGH_GEAR);
-  }
-
-  public void setLowGear() {
-    changeGear(Constants.Shooter.LOW_GEAR);
-  }
-
-  private void changeGear(DoubleSolenoid.Value gear) {
-    piston.set(gear);
-  }
-
   public void reverseFlyWheel() {
     this.setFlyWheelMotorVal(shooter.REVERSE_FLYWHEEL_MOTOR_VALUE);
   }