From: Nadia Anees Date: Tue, 31 Jan 2017 04:14:33 +0000 (-0800) Subject: I wrote code for incrreasing and decreasing shooting speed and added necessary consta... X-Git-Url: http://challenge-bot.com/repos/?p=3501%2F2017steamworks;a=commitdiff_plain;h=ad7e6b1e386d82e35d6049e211b7c1ae3efe705d I wrote code for incrreasing and decreasing shooting speed and added necessary constant variables --- diff --git a/src/org/usfirst/frc/team3501/robot/commands/shooter/DecreaseShootingSpeed.java b/src/org/usfirst/frc/team3501/robot/commands/shooter/DecreaseShootingSpeed.java index 23ac1a8..3bd4efd 100644 --- a/src/org/usfirst/frc/team3501/robot/commands/shooter/DecreaseShootingSpeed.java +++ b/src/org/usfirst/frc/team3501/robot/commands/shooter/DecreaseShootingSpeed.java @@ -1,5 +1,8 @@ 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; /** @@ -10,35 +13,35 @@ import edu.wpi.first.wpilibj.command.Command; * flywheel is run, it will run at the decreased shooting speed */ public class DecreaseShootingSpeed extends Command { + private Shooter shooter = Robot.getShooter(); + public DecreaseShootingSpeed() { } - // Called just before this Command runs the first time @Override protected void initialize() { + shooter.CURRENT_SHOOTING_SPEED -= shooter.SHOOTING_SPEED_INCREMENT; + } - // Called repeatedly when this Command is scheduled to run @Override protected void execute() { } - // 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() { - // TODO Auto-generated method stub - return false; + return true; + } } diff --git a/src/org/usfirst/frc/team3501/robot/commands/shooter/IncreaseShootingSpeed.java b/src/org/usfirst/frc/team3501/robot/commands/shooter/IncreaseShootingSpeed.java index aeb74ec..85bd3bd 100644 --- a/src/org/usfirst/frc/team3501/robot/commands/shooter/IncreaseShootingSpeed.java +++ b/src/org/usfirst/frc/team3501/robot/commands/shooter/IncreaseShootingSpeed.java @@ -1,5 +1,8 @@ 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; /** @@ -10,35 +13,34 @@ import edu.wpi.first.wpilibj.command.Command; * flywheel is run, it will run at the increased shooting speed */ public class IncreaseShootingSpeed extends Command { + private Shooter shooter = Robot.getShooter(); + public IncreaseShootingSpeed() { } - // Called just before this Command runs the first time @Override protected void initialize() { + shooter.CURRENT_SHOOTING_SPEED += shooter.SHOOTING_SPEED_INCREMENT; } - // Called repeatedly when this Command is scheduled to run @Override protected void execute() { } - // 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() { - // TODO Auto-generated method stub - return false; + + return true; } } diff --git a/src/org/usfirst/frc/team3501/robot/commands/shooter/RunFlyWheel.java b/src/org/usfirst/frc/team3501/robot/commands/shooter/RunFlyWheel.java index 203f9dc..7850688 100644 --- a/src/org/usfirst/frc/team3501/robot/commands/shooter/RunFlyWheel.java +++ b/src/org/usfirst/frc/team3501/robot/commands/shooter/RunFlyWheel.java @@ -1,6 +1,7 @@ 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; @@ -12,8 +13,8 @@ import edu.wpi.first.wpilibj.command.Command; * @author Shaina */ public class RunFlyWheel extends Command { + private Shooter shooter = Robot.getShooter(); Timer timer; - private double motorVal; private double time; /** @@ -24,11 +25,10 @@ public class RunFlyWheel extends Command { * @param time * in seconds, amount of time to run fly wheel motor */ - public RunFlyWheel(double motorVal, double time) { - requires(Robot.getShooter()); + public RunFlyWheel(double time) { + requires(shooter); timer = new Timer(); - this.motorVal = motorVal; this.time = time; } @@ -36,7 +36,7 @@ public class RunFlyWheel extends Command { @Override protected void initialize() { timer.start(); - Robot.getShooter().setFlyWheelMotorVal(motorVal); + shooter.setFlyWheelMotorVal(shooter.CURRENT_SHOOTING_SPEED); } // Called repeatedly when this Command is scheduled to run @@ -47,7 +47,7 @@ public class RunFlyWheel extends Command { // Called once after isFinished returns true @Override protected void end() { - Robot.getShooter().stopFlyWheel(); + shooter.stopFlyWheel(); } // Called when another command which requires one or more of the same diff --git a/src/org/usfirst/frc/team3501/robot/commands/shooter/RunIndexWheelContinuous.java b/src/org/usfirst/frc/team3501/robot/commands/shooter/RunIndexWheelContinuous.java index b4eed57..1bf1c6f 100644 --- a/src/org/usfirst/frc/team3501/robot/commands/shooter/RunIndexWheelContinuous.java +++ b/src/org/usfirst/frc/team3501/robot/commands/shooter/RunIndexWheelContinuous.java @@ -1,6 +1,7 @@ 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; @@ -17,7 +18,7 @@ import edu.wpi.first.wpilibj.command.Command; * @author Shaina */ public class RunIndexWheelContinuous extends Command { - private double motorVal; + private Shooter shooter = Robot.getShooter(); /** * See JavaDoc comment in class for details @@ -25,14 +26,14 @@ public class RunIndexWheelContinuous extends Command { * @param motorVal * value range from -1 to 1 */ - public RunIndexWheelContinuous(double motorVal) { - this.motorVal = motorVal; + public RunIndexWheelContinuous() { + } // Called just before this Command runs the first time @Override protected void initialize() { - Robot.getShooter().setIndexWheelMotorVal(motorVal); + shooter.setIndexWheelMotorVal(shooter.CURRENT_SHOOTING_SPEED); } // Called repeatedly when this Command is scheduled to run diff --git a/src/org/usfirst/frc/team3501/robot/subsystems/Shooter.java b/src/org/usfirst/frc/team3501/robot/subsystems/Shooter.java index 06073a7..73c1b23 100644 --- a/src/org/usfirst/frc/team3501/robot/subsystems/Shooter.java +++ b/src/org/usfirst/frc/team3501/robot/subsystems/Shooter.java @@ -10,9 +10,15 @@ public class Shooter extends Subsystem { private static Shooter shooter; private final CANTalon flyWheel, indexWheel; + public static final double DEFAULT_SHOOTING_SPEED = 0; + public static double CURRENT_SHOOTING_SPEED; + + public static final double SHOOTING_SPEED_INCREMENT = 0; + private Shooter() { flyWheel = new CANTalon(Constants.Shooter.FLY_WHEEL); indexWheel = new CANTalon(Constants.Shooter.INDEX_WHEEL); + } /**