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 RunFlyWheel extends Command {
private Shooter shooter = Robot.getShooter();
- Timer timer;
private double time;
/**
*/
public RunFlyWheel(double time) {
requires(shooter);
-
- timer = new Timer();
this.time = time;
}
// Called just before this Command runs the first time
@Override
protected void initialize() {
- timer.start();
- shooter.setFlyWheelMotorVal(shooter.CURRENT_SHOOTING_SPEED);
}
// Called repeatedly when this Command is scheduled to run
@Override
protected void execute() {
+ shooter.setFlyWheelMotorVal(shooter.CURRENT_SHOOTING_SPEED);
}
// Called once after isFinished returns true
@Override
protected boolean isFinished() {
- return timer.get() >= time;
+ return timeSinceInitialized() >= time;
}
}
package org.usfirst.frc.team3501.robot.commands.shooter;
import org.usfirst.frc.team3501.robot.Robot;
+import org.usfirst.frc.team3501.robot.subsystems.Shooter;
import edu.wpi.first.wpilibj.command.Command;
* @author Shaina
*/
public class RunFlyWheelContinuous extends Command {
- private double motorVal;
+ private Shooter shooter = Robot.getShooter();
/**
* See JavaDoc comment in class for details
* @param motorVal
* value range from -1 to 1
*/
- public RunFlyWheelContinuous(double motorVal) {
- this.motorVal = motorVal;
+ public RunFlyWheelContinuous() {
+ requires(shooter);
}
// Called just before this Command runs the first time
@Override
protected void initialize() {
- Robot.getShooter().setFlyWheelMotorVal(motorVal);
}
// Called repeatedly when this Command is scheduled to run
@Override
protected void execute() {
+ shooter.setFlyWheelMotorVal(shooter.CURRENT_SHOOTING_SPEED);
}
// Called once after isFinished returns true
package org.usfirst.frc.team3501.robot.commands.shooter;
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;
/**
* @author Shaina
*/
public class RunIndexWheel extends Command {
- Timer timer;
+ private Shooter shooter = Robot.getShooter();
private double time;
- private double motorVal;
/**
* See JavaDoc comment in class for details
* @param time
* in seconds, amount of time to run index wheel motor
*/
- public RunIndexWheel(double motorVal, double time) {
- requires(Robot.getShooter());
-
- timer = new Timer();
- this.motorVal = motorVal;
+ public RunIndexWheel(double time) {
+ requires(shooter);
this.time = time;
}
// Called just before this Command runs the first time
@Override
protected void initialize() {
- timer.start();
- Robot.getShooter().setIndexWheelMotorVal(motorVal);
}
// Called repeatedly when this Command is scheduled to run
@Override
protected void execute() {
+ shooter.setIndexWheelMotorVal(shooter.DEFAULT_INDEXING_SPEED);
}
// Called once after isFinished returns true
@Override
protected void end() {
- Robot.getShooter().stopIndexWheel();
+ shooter.stopIndexWheel();
}
// Called when another command which requires one or more of the same
@Override
protected boolean isFinished() {
- return timer.get() >= time;
+ return timeSinceInitialized() >= time;
}
}
* value range from -1 to 1
*/
public RunIndexWheelContinuous() {
-
+ requires(shooter);
}
// Called just before this Command runs the first time
@Override
protected void initialize() {
- shooter.setIndexWheelMotorVal(shooter.CURRENT_SHOOTING_SPEED);
}
// Called repeatedly when this Command is scheduled to run
@Override
protected void execute() {
+ shooter.setIndexWheelMotorVal(shooter.DEFAULT_INDEXING_SPEED);
}
// Called once after isFinished returns true
private static Shooter shooter;
private final CANTalon flyWheel, indexWheel;
+ public static final double DEFAULT_INDEXING_SPEED = 0;
public static final double DEFAULT_SHOOTING_SPEED = 0;
public static double CURRENT_SHOOTING_SPEED;