public final static int HALL_EFFECT_PORT = 9;
- public static final int PISTON_MODULE = 10, PISTON_FORWARD = 0,
- PISTON_REVERSE = 1;
+ public final static int TOGGLE_INDEXER = 8;
+
+ public static final int PISTON_MODULE = 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 final Value HIGH_GEAR = DoubleSolenoid.Value.kForward;
public static final Value LOW_GEAR = DoubleSolenoid.Value.kReverse;
+ public final static int TOGGLE_DRIVE_PISTON = 7;
+
// MOTOR CONTROLLERS
public static final int FRONT_LEFT = 1;
public static final int FRONT_RIGHT = 3;
package org.usfirst.frc.team3501.robot;
-import java.awt.event.KeyEvent;
-import java.awt.event.KeyListener;
-
import org.usfirst.frc.team3501.robot.commands.climber.ToggleWinch;
+import org.usfirst.frc.team3501.robot.commands.driving.ToggleDrivePiston;
import org.usfirst.frc.team3501.robot.commands.driving.ToggleGear;
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.ReverseIndexWheelContinuous;
import org.usfirst.frc.team3501.robot.commands.shooter.RunFlyWheelContinuous;
import org.usfirst.frc.team3501.robot.commands.shooter.RunIndexWheelContinuous;
-import org.usfirst.frc.team3501.robot.utils.ChangeCameraView;
+import org.usfirst.frc.team3501.robot.commands.shooter.ToggleIndexerPiston;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.buttons.Button;
import edu.wpi.first.wpilibj.buttons.JoystickButton;
-public class OI implements KeyListener {
+public class OI /* implements KeyListener */ {
private static OI oi;
public static Joystick leftJoystick;
public static Joystick rightJoystick;
private static Button changeCam;
+ private static Button togglePiston;
+ private static Button toggleDriveTrainPiston;
+
public OI() {
+
leftJoystick = new Joystick(Constants.OI.LEFT_STICK_PORT);
rightJoystick = new Joystick(Constants.OI.RIGHT_STICK_PORT);
runIndexWheel = new JoystickButton(rightJoystick,
Constants.OI.RUN_INDEXWHEEL_PORT);
- runIndexWheel.whileHeld(new RunIndexWheelContinuous());
+ runIndexWheel.whileHeld(
+ new RunIndexWheelContinuous()); /*
+ * { double shooterSpeed =
+ * (Robot.getShooter()).getShooterRPM();
+ * if (shooterSpeed > 0) {
+ * Robot.getShooter().runIndexWheel(); }
+ * });
+ */
reverseIndexWheel = new JoystickButton(rightJoystick,
Constants.OI.REVERSE_INDEXWHEEL_PORT);
Constants.OI.DECREASE_SHOOTER_SPEED_PORT);
decreaseShooterSpeed.whenPressed(new DecreaseShootingSpeed());
- changeCam = new JoystickButton(rightJoystick,
- Constants.OI.CHANGE_CAMERA_VIEW);
- changeCam.toggleWhenPressed(new ChangeCameraView());
+ /*
+ * changeCam = new JoystickButton(rightJoystick,
+ * Constants.OI.CHANGE_CAMERA_VIEW); changeCam.toggleWhenPressed(new
+ * ChangeCameraView());
+ */
+
+ togglePiston = new JoystickButton(rightJoystick,
+ Constants.Shooter.TOGGLE_INDEXER);
+ togglePiston.whenPressed(new ToggleIndexerPiston());
+
+ toggleDriveTrainPiston = new JoystickButton(rightJoystick,
+ Constants.DriveTrain.TOGGLE_DRIVE_PISTON);
+ toggleDriveTrainPiston.whenPressed(new ToggleDrivePiston());
}
public static OI getOI() {
return oi;
}
- @Override
- public void keyTyped(KeyEvent e) {
-
- }
-
- @Override
- public void keyPressed(KeyEvent e) {
- // TODO Auto-generated method stub
-
- }
-
- @Override
- public void keyReleased(KeyEvent e) {
- // TODO Auto-generated method stub
+ /*
+ * @Override public void keyPressed(KeyEvent e) { if (e.getKeyCode() ==
+ * KeyEvent.VK_Z) { // Robot.swapCameraFeed();
+ * Robot.getShooter().runIndexWheel(); } }
+ *
+ * @Override public void keyReleased(KeyEvent e) { if (e.getKeyCode() ==
+ * KeyEvent.VK_Z) { // Robot.swapCameraFeed();
+ * Robot.getShooter().stopIndexWheel(); } }
+ *
+ * @Override public void keyTyped(KeyEvent e) { }
+ */
- }
}
--- /dev/null
+package org.usfirst.frc.team3501.robot.commands.driving;
+
+import org.usfirst.frc.team3501.robot.Constants;
+import org.usfirst.frc.team3501.robot.Robot;
+import org.usfirst.frc.team3501.robot.subsystems.DriveTrain;
+import edu.wpi.first.wpilibj.command.Command;
+
+public class ToggleDrivePiston extends Command {
+ private DriveTrain driveTrain = Robot.getDriveTrain();
+
+ /**
+ * See JavaDoc comment in class for details
+ *
+ * @param motorVal
+ * value range from -1 to 1
+ */
+ public ToggleDrivePiston() {
+ requires(driveTrain);
+ }
+
+ // Called just before this Command runs the first time
+ @Override
+ protected void initialize() {
+ }
+
+ // Called repeatedly when this Command is scheduled to run
+ @Override
+ protected void execute() {
+ if (DriveTrain.getDriveTrain()
+ .getLeftGearPistonValue() == Constants.DriveTrain.HIGH_GEAR) {
+ DriveTrain.getDriveTrain().setLowGear();
+ } else {
+ DriveTrain.getDriveTrain().setHighGear();
+ }
+
+ // check to make sure that both pistons are set to the same gear. Otherwise,
+ // the code must be changed
+ }
+
+ // Called once after isFinished returns true
+ @Override
+ protected void end() {
+ }
+
+ // Called when another command which requires one or more of the same
+ // subsystems is scheduled to run
+ @Override
+ protected void interrupted() {
+ end();
+ }
+
+ @Override
+ protected boolean isFinished() {
+ return false;
+
+ }
+
+}
package org.usfirst.frc.team3501.robot.commands.shooter;
-import org.usfirst.frc.team3501.robot.Constants;
import org.usfirst.frc.team3501.robot.Robot;
import org.usfirst.frc.team3501.robot.subsystems.Shooter;
-import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.command.Command;
/**
*/
public class RunIndexWheelContinuous extends Command {
private Shooter shooter = Robot.getShooter();
- private Timer t = new Timer();
+ // private Timer t = new Timer();
/**
* See JavaDoc comment in class for details
*/
public RunIndexWheelContinuous() {
requires(shooter);
+ // t.start();
}
// Called just before this Command runs the first time
@Override
protected void initialize() {
- t.reset();
+ // t.reset();
}
// Called repeatedly when this Command is scheduled to run
@Override
protected void execute() {
- if (t.get() % 1 == 0) {
- if (Shooter.getShooter().getPistonValue() == Constants.Shooter.LOW_GEAR) {
- Shooter.getShooter().setHighGear();
- } else {
- Shooter.getShooter().setLowGear();
- }
- }
+ /*
+ * if (t.get() >= 4) { if (Shooter.getShooter().getPistonValue() ==
+ * Constants.Shooter.LOW_GEAR) { Shooter.getShooter().setHighGear(); } else
+ * { Shooter.getShooter().setLowGear(); } }
+ */
double shooterSpeed = shooter.getShooterRPM();
if (shooterSpeed > 0)
--- /dev/null
+package org.usfirst.frc.team3501.robot.commands.shooter;
+
+import org.usfirst.frc.team3501.robot.Constants;
+import org.usfirst.frc.team3501.robot.Robot;
+import org.usfirst.frc.team3501.robot.subsystems.Shooter;
+
+import edu.wpi.first.wpilibj.command.Command;
+
+public class ToggleIndexerPiston extends Command {
+ private Shooter shooter = Robot.getShooter();
+
+ /**
+ * See JavaDoc comment in class for details
+ *
+ * @param motorVal
+ * value range from -1 to 1
+ */
+ public ToggleIndexerPiston() {
+ requires(shooter);
+ }
+
+ // Called just before this Command runs the first time
+ @Override
+ protected void initialize() {
+ }
+
+ // Called repeatedly when this Command is scheduled to run
+ @Override
+ protected void execute() {
+ if (Shooter.getShooter().getPistonValue() == Constants.Shooter.LOW_GEAR) {
+ Shooter.getShooter().setHighGear();
+ } else {
+ Shooter.getShooter().setLowGear();
+ }
+ }
+
+ // Called once after isFinished returns true
+ @Override
+ protected void end() {
+ }
+
+ // Called when another command which requires one or more of the same
+ // subsystems is scheduled to run
+ @Override
+ protected void interrupted() {
+ end();
+ }
+
+ @Override
+ protected boolean isFinished() {
+ return false;
+
+ }
+
+}