projects
/
3501
/
2017steamworks
/ commitdiff
commit
grep
author
committer
pickaxe
?
search:
re
summary
|
shortlog
|
log
|
commit
| commitdiff |
tree
raw
|
patch
|
inline
| side by side (parent:
d7042be
)
Implement getter and setter methods for current shooting speed
Nadia/flywheel
author
Nadia Anees
<n.anees655@gmail.com>
Sat, 11 Feb 2017 04:02:26 +0000
(20:02 -0800)
committer
Cindy Zhang
<cindyzyx9@gmail.com>
Sun, 19 Feb 2017 21:36:01 +0000
(13:36 -0800)
src/org/usfirst/frc/team3501/robot/commands/shooter/DecreaseShootingSpeed.java
patch
|
blob
|
blame
|
history
src/org/usfirst/frc/team3501/robot/commands/shooter/IncreaseShootingSpeed.java
patch
|
blob
|
blame
|
history
src/org/usfirst/frc/team3501/robot/commands/shooter/ResetShootingSpeed.java
patch
|
blob
|
blame
|
history
src/org/usfirst/frc/team3501/robot/commands/shooter/RunFlyWheel.java
patch
|
blob
|
blame
|
history
src/org/usfirst/frc/team3501/robot/commands/shooter/RunFlyWheelContinuous.java
patch
|
blob
|
blame
|
history
src/org/usfirst/frc/team3501/robot/subsystems/Shooter.java
patch
|
blob
|
blame
|
history
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 3bd4efd7490e7462306cbe05fb75ebff63c15516..2edc9ec2586dba2f5f8c4d1031dff36756e17f74 100644
(file)
--- a/
src/org/usfirst/frc/team3501/robot/commands/shooter/DecreaseShootingSpeed.java
+++ b/
src/org/usfirst/frc/team3501/robot/commands/shooter/DecreaseShootingSpeed.java
@@
-21,8
+21,8
@@
public class DecreaseShootingSpeed extends Command {
@Override
protected void initialize() {
@Override
protected void initialize() {
- shooter.
CURRENT_SHOOTING_SPEED -= shooter.SHOOTING_SPEED_INCREMENT;
-
+ shooter.
setCurrentShootingSpeed(
+ shooter.getCurrentShootingSpeed() - shooter.SHOOTING_SPEED_INCREMENT);
}
@Override
}
@Override
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 85bd3bd39dbedf9af5418853babcdb49edf7a4b4..dcd4aa744898821d0afd9c4bb7d5df5d1ec8fea8 100644
(file)
--- a/
src/org/usfirst/frc/team3501/robot/commands/shooter/IncreaseShootingSpeed.java
+++ b/
src/org/usfirst/frc/team3501/robot/commands/shooter/IncreaseShootingSpeed.java
@@
-21,7
+21,8
@@
public class IncreaseShootingSpeed extends Command {
@Override
protected void initialize() {
@Override
protected void initialize() {
- shooter.CURRENT_SHOOTING_SPEED += shooter.SHOOTING_SPEED_INCREMENT;
+ shooter.setCurrentShootingSpeed(
+ shooter.getCurrentShootingSpeed() + shooter.SHOOTING_SPEED_INCREMENT);
}
@Override
}
@Override
diff --git
a/src/org/usfirst/frc/team3501/robot/commands/shooter/ResetShootingSpeed.java
b/src/org/usfirst/frc/team3501/robot/commands/shooter/ResetShootingSpeed.java
index 7a2f95091bcd4f79c1116f072734b2728901c763..d8f016218ae79a590db2d380d3d71eda13babfe8 100644
(file)
--- a/
src/org/usfirst/frc/team3501/robot/commands/shooter/ResetShootingSpeed.java
+++ b/
src/org/usfirst/frc/team3501/robot/commands/shooter/ResetShootingSpeed.java
@@
-20,7
+20,7
@@
public class ResetShootingSpeed extends Command {
@Override
protected void initialize() {
@Override
protected void initialize() {
- shooter.
CURRENT_SHOOTING_SPEED = shooter.DEFAULT_SHOOTING_SPEED
;
+ shooter.
setCurrentShootingSpeed(shooter.DEFAULT_SHOOTING_SPEED)
;
}
@Override
}
@Override
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 a20af8e63badd3bfee9722e5037c9771b60a8a52..442897aa9e15eb71f22544f8b2170bb32f2d5b35 100644
(file)
--- a/
src/org/usfirst/frc/team3501/robot/commands/shooter/RunFlyWheel.java
+++ b/
src/org/usfirst/frc/team3501/robot/commands/shooter/RunFlyWheel.java
@@
-34,7
+34,7
@@
public class RunFlyWheel extends Command {
this.wheelController.setDoneRange(0.5);
this.wheelController.setMaxOutput(1.0);
this.wheelController.setMinDoneCycles(3);
this.wheelController.setDoneRange(0.5);
this.wheelController.setMaxOutput(1.0);
this.wheelController.setMinDoneCycles(3);
- this.target = this.shooter.
CURRENT_SHOOTING_SPEED
;
+ this.target = this.shooter.
getCurrentShootingSpeed()
;
}
// Called just before this Command runs the first time
}
// Called just before this Command runs the first time
diff --git
a/src/org/usfirst/frc/team3501/robot/commands/shooter/RunFlyWheelContinuous.java
b/src/org/usfirst/frc/team3501/robot/commands/shooter/RunFlyWheelContinuous.java
index 2ae906c7be9753d2ba15de5b2994ccf765273a06..ff4f65960c69a50ad6114e7993260aa131bee7ff 100644
(file)
--- a/
src/org/usfirst/frc/team3501/robot/commands/shooter/RunFlyWheelContinuous.java
+++ b/
src/org/usfirst/frc/team3501/robot/commands/shooter/RunFlyWheelContinuous.java
@@
-36,7
+36,7
@@
public class RunFlyWheelContinuous extends Command {
this.wheelController.setDoneRange(0.5);
this.wheelController.setMaxOutput(1.0);
this.wheelController.setMinDoneCycles(3);
this.wheelController.setDoneRange(0.5);
this.wheelController.setMaxOutput(1.0);
this.wheelController.setMinDoneCycles(3);
- this.target = this.shooter.
CURRENT_SHOOTING_SPEED
;
+ this.target = this.shooter.
getCurrentShootingSpeed()
;
}
@Override
}
@Override
diff --git
a/src/org/usfirst/frc/team3501/robot/subsystems/Shooter.java
b/src/org/usfirst/frc/team3501/robot/subsystems/Shooter.java
index 4869775e82dc88ccb8231063172da15e9839c03f..b9ccb42dff3967cabcfd551a0d71bb7c1ca31ad9 100644
(file)
--- a/
src/org/usfirst/frc/team3501/robot/subsystems/Shooter.java
+++ b/
src/org/usfirst/frc/team3501/robot/subsystems/Shooter.java
@@
-79,6
+79,14
@@
public class Shooter extends Subsystem {
indexWheel.set(0);
}
indexWheel.set(0);
}
+ public double getCurrentShootingSpeed() {
+ return CURRENT_SHOOTING_SPEED;
+ }
+
+ public void setCurrentShootingSpeed(double Value) {
+ CURRENT_SHOOTING_SPEED = Value;
+ }
+
@Override
protected void initDefaultCommand() {
@Override
protected void initDefaultCommand() {