public final static int RIGHT_STICK_PORT = 1;
// Need to fill in the port numbers of the following buttons
- public final static int TOGGLE_WINCH_PORT = 0;
public final static int TOGGLE_FLYWHEEL_PORT = 4;
public final static int RUN_INDEXWHEEL_PORT = 1;
public final static int REVERSE_INDEXWHEEL_PORT = 2;
public final static int REVERSE_INTAKE_PORT = 4;
public static final int INCREASE_SHOOTER_SPEED_PORT = 6;
public static final int DECREASE_SHOOTER_SPEED_PORT = 2;
+
public static final int CHANGE_CAMERA_VIEW = 6;
+
+ public static final int BRAKE_CANTALONS_PORT = 5;
+ public static final int COAST_CANTALONS_PORT = 3;
+
}
public static class Shooter {
public final static int TOGGLE_INDEXER = 8;
- public static final int PISTON_MODULE = 10, PISTON_FORWARD = 4,
+ 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 {
// GEARS
public static final int PISTON_MODULE = 10, LEFT_GEAR_PISTON_FORWARD = 0,
- LEFT_GEAR_PISTON_REVERSE = 1, RIGHT_GEAR_PISTON_FORWARD = 2,
- RIGHT_GEAR_PISTON_REVERSE = 3;
+ LEFT_GEAR_PISTON_REVERSE = 1, RIGHT_GEAR_PISTON_FORWARD = 3,
+ RIGHT_GEAR_PISTON_REVERSE = 2;
public static final Value HIGH_GEAR = DoubleSolenoid.Value.kForward;
public static final Value LOW_GEAR = DoubleSolenoid.Value.kReverse;
package org.usfirst.frc.team3501.robot;
-import org.usfirst.frc.team3501.robot.commands.climber.ToggleWinch;
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;
private static OI oi;
public static Joystick leftJoystick;
public static Joystick rightJoystick;
- public static Button toggleWinch;
public static Button runIndexWheel;
public static Button reverseIndexWheel;
private static Button togglePiston;
private static Button toggleDriveTrainPiston;
+ public static Button brakeCANTalons;
+ public static Button coastCANTalons;
+
public OI() {
leftJoystick = new Joystick(Constants.OI.LEFT_STICK_PORT);
Constants.OI.REVERSE_INTAKE_PORT);
reverseIntake.whileHeld(new ReverseIntakeContinuous());
- toggleWinch = new JoystickButton(leftJoystick,
- Constants.OI.TOGGLE_WINCH_PORT);
- toggleWinch.whenPressed(new ToggleWinch());
-
increaseShooterSpeed = new JoystickButton(leftJoystick,
Constants.OI.INCREASE_SHOOTER_SPEED_PORT);
increaseShooterSpeed.whenPressed(new IncreaseShootingSpeed());
toggleDriveTrainPiston = new JoystickButton(rightJoystick,
Constants.DriveTrain.TOGGLE_DRIVE_PISTON);
toggleDriveTrainPiston.whenPressed(new ToggleGear());
+
+ brakeCANTalons = new JoystickButton(rightJoystick,
+ Constants.OI.BRAKE_CANTALONS_PORT);
+ brakeCANTalons.whenPressed(new BrakeCANTalons());
+
+ coastCANTalons = new JoystickButton(rightJoystick,
+ Constants.OI.COAST_CANTALONS_PORT);
+ coastCANTalons.whenPressed(new CoastCANTalons());
}
public static OI getOI() {
oi = OI.getOI();
shooter = Shooter.getShooter();
intake = Intake.getIntake();
+
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() {
@Override
public void autonomousInit() {
driveTrain.setHighGear();
+ driveTrain.setCANTalonsBrakeMode(driveTrain.DRIVE_COAST_MODE);
}
@Override
@Override
public void teleopInit() {
+ 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());
+ SmartDashboard.putNumber("right encoder",
+ driveTrain.getRightEncoderDistance());
SmartDashboard.putNumber("angle", driveTrain.getAngle());
SmartDashboard.putNumber("voltage",
DriverStation.getInstance().getBatteryVoltage());
SmartDashboard.putNumber("rpm", shooter.getShooterRPM());
- SmartDashboard.putNumber("motor value", shooter.getCurrentShootingSpeed());
+ SmartDashboard.putNumber("target shooting",
+ shooter.getTargetShootingSpeed());
}
}
--- /dev/null
+package org.usfirst.frc.team3501.robot.commandgroups;
+
+import org.usfirst.frc.team3501.robot.Constants;
+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.Timer;
+import edu.wpi.first.wpilibj.command.CommandGroup;
+import edu.wpi.first.wpilibj.command.WaitCommand;
+
+/**
+ * // Robot starts in middle, goes to the hopper, then boiler,then shoots during
+ * auton
+ */
+public class AutonHopperShoot extends CommandGroup {
+ // If red, direction is right; if blue, direction is left
+ private static final Direction DIRECTION_TO_HOPPER = Constants.Direction.LEFT;
+ // If red, direction is left; if blue, direction is right
+ private static final Direction DIRECTION_TO_BOILER = Constants.Direction.RIGHT;
+
+ private Timer timer;
+
+ public AutonHopperShoot() {
+ timer = new Timer();
+ // Robot drives from center to front of airship
+ addSequential(new DriveDistance(78.5, 2.7));
+ // Robot turns towards hopper
+ addSequential(new TurnForAngle(90.0, DIRECTION_TO_HOPPER, 2.5));
+ // Robot drives into hopper switch
+ addSequential(new DriveDistance(42.12, 5.25));
+ addSequential(new WaitCommand(1));
+ // Robot backs up from switch
+ addSequential(new DriveDistance(-25.0, 2.9));
+ // Robot turns towards the boiler
+ addSequential(new TurnForAngle(90.0, DIRECTION_TO_HOPPER, 5.0));
+ // Robot drives to boiler
+ addSequential(new DriveDistance(90, 5.0));
+ // Robot turns parallel to boiler
+ addSequential(new TurnForAngle(45, DIRECTION_TO_BOILER, 5.0));
+ // Shoot
+ addSequential(new Shoot(15 - timeSinceInitialized()));
+ }
+
+}
--- /dev/null
+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;
+
+/**
+ *
+ */
+public class AutonShoot extends CommandGroup {
+
+ private static final int ROBOT_WIDTH = 40; // inches
+ private static final int ROBOT_LENGTH = 36; // inches
+
+ public AutonShoot() {
+ addSequential(
+ new DriveDistance(37.12 + (ROBOT_WIDTH / 2) - (ROBOT_LENGTH / 2), 5));
+ addSequential(new TurnForAngle(135, Direction.LEFT, 10));
+ addSequential(new DriveDistance(
+ (37.12 + (ROBOT_WIDTH / 2)) * Math.sqrt(2) - 26.25 - (ROBOT_LENGTH / 2),
+ 10));
+ addSequential(new Shoot(15 - timeSinceInitialized()));
+ }
+}
package org.usfirst.frc.team3501.robot.commandgroups;
+import org.usfirst.frc.team3501.robot.commands.shooter.RunFlyWheel;
+import org.usfirst.frc.team3501.robot.commands.shooter.RunIndexWheel;
+
import edu.wpi.first.wpilibj.command.CommandGroup;
+import edu.wpi.first.wpilibj.command.WaitCommand;
/**
*
*/
public class Shoot extends CommandGroup {
- public Shoot() {
- // Add Commands here:
- // e.g. addSequential(new Command1());
- // addSequential(new Command2());
- // these will run in order.
-
- // To run multiple commands at the same time,
- // use addParallel()
- // e.g. addParallel(new Command1());
- // addSequential(new Command2());
- // Command1 and Command2 will run in parallel.
-
- // A command group will require all of the subsystems that each member
- // would require.
- // e.g. if Command1 requires chassis, and Command2 requires arm,
- // a CommandGroup containing them would require both the chassis and the
- // arm.
- }
+ public Shoot(double time) {
+ addParallel(new RunFlyWheel(time));
+ addSequential(new WaitCommand(2));
+ addParallel(new RunIndexWheel(time - 2));
+ }
}
@Override
protected boolean isFinished() {
- return Robot.getOI().toggleWinch.get();
+ return false;
}
@Override
--- /dev/null
+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() {
+ }
+}
--- /dev/null
+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() {
+ }
+}
this.maxTimeOut = maxTimeOut;
this.target = Math.abs(angle);
- this.gyroP = driveTrain.turnP;
- this.gyroI = driveTrain.turnI;
- this.gyroD = driveTrain.turnD;
+ if (angle > 90) {
+ this.gyroP = driveTrain.largeTurnP;
+ this.gyroI = driveTrain.largeTurnI;
+ this.gyroD = driveTrain.largeTurnD;
+ } else {
+ this.gyroP = driveTrain.smallTurnP;
+ this.gyroI = driveTrain.smallTurnI;
+ this.gyroD = driveTrain.smallTurnD;
+ }
this.gyroController = new PIDController(this.gyroP, this.gyroI, this.gyroD);
this.gyroController.setDoneRange(1);
@Override
protected void initialize() {
- shooter.decrementCurrentShootingSpeed();
+ shooter.decrementTargetShootingSpeed();
}
@Override
@Override
protected void initialize() {
- shooter.incrementCurrentShootingSpeed();
+ shooter.incrementTargetShootingSpeed();
}
@Override
@Override
protected void initialize() {
- shooter.resetCurrentShootingSpeed();
+ shooter.resetTargetShootingSpeed();
}
@Override
-
package org.usfirst.frc.team3501.robot.commands.shooter;
import org.usfirst.frc.team3501.robot.Robot;
import edu.wpi.first.wpilibj.command.Command;
/**
- * This command runs the fly wheel at a specific speed using a PID Controller
- * for accuracy for a given time. The fly wheel is intended to shoot balls fed
- * by the intake wheel.
+ * This command runs the fly wheel continuously at a set speed using a PID
+ * Controller when OI button managing fly wheel is pressed. The command will run
+ * the fly wheel motor until the button triggering it is released.
+ *
+ * Should only be run from the operator interface.
+ *
+ * pre-condition: This command must be run by a button in OI, with
+ * button.whileHeld(...).
*
* @author Shaina & Chris
*/
public class RunFlyWheel extends Command {
private Shooter shooter = Robot.getShooter();
- private double maxTimeOut;
+ double time;
private PIDController wheelController;
- private double wheelP;
- private double wheelI;
- private double wheelD;
- private double target;
- private double shooterSpeed = 0;
-
- public RunFlyWheel(double maxTimeOut) {
- this.wheelP = this.shooter.wheelP;
- this.wheelI = this.shooter.wheelI;
- this.wheelD = this.shooter.wheelD;
- this.wheelController = new PIDController(this.wheelP, this.wheelI,
- this.wheelD);
- this.wheelController.setDoneRange(0.5);
- this.wheelController.setMaxOutput(1.0);
- this.wheelController.setMinDoneCycles(3);
- this.target = this.shooter.getCurrentShootingSpeed();
+ public RunFlyWheel(double time) {
+ this.time = time;
}
- // Called just before this Command runs the first time
@Override
protected void initialize() {
- this.wheelController.setSetPoint(this.target);
+ shooter.initializePIDController();
}
- // Called repeatedly when this Command is scheduled to run
@Override
protected void execute() {
- double calculatedShooterIncrement = this.wheelController
- .calcPID(this.shooter.getShooterRPM());
- shooterSpeed += calculatedShooterIncrement;
- this.shooter.setFlyWheelMotorVal(shooterSpeed);
+ shooter.setFlyWheelMotorVal(shooter.calculateShooterSpeed());
}
- // Make this return true when this Command no longer needs to run execute()
@Override
protected boolean isFinished() {
- return timeSinceInitialized() >= maxTimeOut;
+ return timeSinceInitialized() >= time;
}
- // Called once after isFinished returns true
@Override
protected void end() {
this.shooter.stopFlyWheel();
}
- // Called when another command which requires one or more of the same
- // subsystems is scheduled to run
@Override
protected void interrupted() {
+ end();
}
}
private Shooter shooter = Robot.getShooter();
private PIDController wheelController;
- private double wheelP;
- private double wheelI;
- private double wheelD;
- private double target;
- private double shooterSpeed = 0;
public RunFlyWheelContinuous() {
- this.wheelP = this.shooter.wheelP;
- this.wheelI = this.shooter.wheelI;
- this.wheelD = this.shooter.wheelD;
- this.wheelController = new PIDController(this.wheelP, this.wheelI,
- this.wheelD);
- this.wheelController.setDoneRange(10);
- this.wheelController.setMaxOutput(1.0);
- this.wheelController.setMinDoneCycles(3);
- this.target = shooter.getCurrentShootingSpeed();
}
@Override
protected void initialize() {
- this.wheelController.setSetPoint(this.target);
+ shooter.initializePIDController();
}
@Override
protected void execute() {
- double calculatedShooterIncrement = this.wheelController
- .calcPID(this.shooter.getShooterRPM());
- shooterSpeed += calculatedShooterIncrement;
- this.shooter.setFlyWheelMotorVal(shooterSpeed);
+ shooter.setFlyWheelMotorVal(shooter.calculateShooterSpeed());
}
@Override
@Override
protected void execute() {
double shooterSpeed = shooter.getShooterRPM();
- if (shooterSpeed > 0)
+ double targetShooterSpeed = shooter.getTargetShootingSpeed();
+ double threshold = shooter.getRPMThreshold();
+ if (Math.abs(shooterSpeed - targetShooterSpeed) <= threshold)
shooter.runIndexWheel();
}
/**
* See JavaDoc comment in class for details
- *
- * @param motorVal
- * value range from -1 to 1
*/
public RunIndexWheelContinuous() {
requires(shooter);
}
- // Called just before this Command runs the first time
@Override
protected void initialize() {
t.start();
}
- // Called repeatedly when this Command is scheduled to run
@Override
protected void execute() {
-
if (t.get() >= 1) {
if (Shooter.getShooter().getPistonValue() == Constants.Shooter.LOW_GEAR) {
Shooter.getShooter().setHighGear();
if (shooter.isShooterRPMWithinRangeOfTargetSpeed(25))
shooter.runIndexWheel();
+
}
- // Called once after isFinished returns true
@Override
protected void end() {
shooter.stopIndexWheel();
}
- // 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;
-
}
}
import edu.wpi.first.wpilibj.command.Subsystem;
public class DriveTrain extends Subsystem {
- public static double driveP = 0.006, driveI = 0.0011, driveD = -0.002;
- public static double turnP = 0.004, turnI = 0.0013, turnD = -0.005;
+ public static double driveP = 0.012, driveI = 0.0011, driveD = -0.002;
+ public static double smallTurnP = 0.004, smallTurnI = 0.0013,
+ smallTurnD = 0.005;
+ public static double largeTurnP = .003, largeTurnI = .0012, largeTurnD = .006;
public static double driveStraightGyroP = 0.01;
public static final double WHEEL_DIAMETER = 4; // inches
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;
// DRIVE METHODS
public void setMotorValues(double left, double right) {
- left = MathLib.restrictToRange(left, 0.0, 1.0);
- right = MathLib.restrictToRange(right, 0.0, 1.0);
+ left = MathLib.restrictToRange(left, -1.0, 1.0);
+ right = MathLib.restrictToRange(right, -1.0, 1.0);
frontLeft.set(left);
rearLeft.set(left);
protected void initDefaultCommand() {
setDefaultCommand(new JoystickDrive());
}
+
+ public void setCANTalonsBrakeMode(boolean mode) {
+ frontLeft.enableBrakeMode(mode);
+ rearLeft.enableBrakeMode(mode);
+
+ frontRight.enableBrakeMode(mode);
+ rearRight.enableBrakeMode(mode);
+ }
}
import org.usfirst.frc.team3501.robot.Constants;
import org.usfirst.frc.team3501.robot.MathLib;
import org.usfirst.frc.team3501.robot.utils.HallEffectSensor;
+import org.usfirst.frc.team3501.robot.utils.PIDController;
import com.ctre.CANTalon;
import edu.wpi.first.wpilibj.command.Subsystem;
public class Shooter extends Subsystem {
- public double wheelP = 0.0001, wheelI = 0, wheelD = 0.0004;
+ public double wheelP = 0.00007, wheelI = 0, wheelD = 0.0008;
private static Shooter shooter;
private static HallEffectSensor hallEffect;
private final CANTalon flyWheel1, flyWheel2, indexWheel;
- private static final double DEFAULT_INDEXING_SPEED = -0.75;
- private static final double DEFAULT_SHOOTING_SPEED = 2800; // rpm
- private static final double SHOOTING_SPEED_INCREMENT = 25;
+ private PIDController wheelController;
+
+ private static final double RPM_THRESHOLD = 10;
+ private static final double DEFAULT_INDEXING_MOTOR_VALUE = -0.75;
+ private static final double DEFAULT_SHOOTING_SPEED = 3100; // rpm
+ private static final double SHOOTING_SPEED_INCREMENT = 50;
private static final int ACCEPTABLE_SHOOTING_DEVIATION = 300;
- private double currentShootingSpeed = DEFAULT_SHOOTING_SPEED;
+ private double targetShootingSpeed = DEFAULT_SHOOTING_SPEED;
+ private double currentShooterMotorValue = 0;
private final DoubleSolenoid piston;
hallEffect = new HallEffectSensor(Constants.Shooter.HALL_EFFECT_PORT, 1);
- piston = new DoubleSolenoid(Constants.Shooter.PISTON_MODULE,
+ piston = new DoubleSolenoid(Constants.Shooter.MODULE_NUMBER,
Constants.Shooter.PISTON_FORWARD, Constants.Shooter.PISTON_REVERSE);
}
}
+ public double getRPMThreshold() {
+ return RPM_THRESHOLD;
+ }
+
public double getShooterRPM() {
return hallEffect.getRPM();
}
- public void setCurrentShootingSpeed(double Value) {
- currentShootingSpeed = Value;
+ public void setTargetShootingSpeed(double Value) {
+ targetShootingSpeed = Value;
}
- public void decrementCurrentShootingSpeed() {
- this.currentShootingSpeed -= this.SHOOTING_SPEED_INCREMENT;
+ public void decrementTargetShootingSpeed() {
+ this.targetShootingSpeed -= this.SHOOTING_SPEED_INCREMENT;
}
- public void incrementCurrentShootingSpeed() {
- this.currentShootingSpeed += this.SHOOTING_SPEED_INCREMENT;
+ public void incrementTargetShootingSpeed() {
+ this.targetShootingSpeed += this.SHOOTING_SPEED_INCREMENT;
}
- public void resetCurrentShootingSpeed() {
- this.currentShootingSpeed = this.DEFAULT_SHOOTING_SPEED;
+ public void resetTargetShootingSpeed() {
+ this.targetShootingSpeed = this.DEFAULT_SHOOTING_SPEED;
}
- public double getCurrentShootingSpeed() {
- return currentShootingSpeed;
+ public double getTargetShootingSpeed() {
+ return targetShootingSpeed;
}
public void reverseIndexWheel() {
- this.setIndexWheelMotorVal(-DEFAULT_INDEXING_SPEED);
+ this.setIndexWheelMotorVal(-DEFAULT_INDEXING_MOTOR_VALUE);
}
public void runIndexWheel() {
- this.setIndexWheelMotorVal(DEFAULT_INDEXING_SPEED);
+ this.setIndexWheelMotorVal(DEFAULT_INDEXING_MOTOR_VALUE);
+ }
+
+ public double calculateShooterSpeed() {
+ this.wheelController.setSetPoint(targetShootingSpeed);
+ double calculatedShooterIncrement = this.wheelController
+ .calcPID(this.getShooterRPM());
+ currentShooterMotorValue += calculatedShooterIncrement;
+ return currentShooterMotorValue;
+ }
+
+ public void initializePIDController() {
+ this.wheelController = new PIDController(wheelP, wheelI, wheelD);
+ this.wheelController.setDoneRange(10);
+ this.wheelController.setMaxOutput(1.0);
+ this.wheelController.setMinDoneCycles(3);
+ this.wheelController.setSetPoint(this.targetShootingSpeed);
+ this.currentShooterMotorValue = 0;
}
public Value getPistonValue() {