diff options
author | Luke Shumaker <lukeshu@sbcglobal.net> | 2016-01-18 15:51:09 -0500 |
---|---|---|
committer | Luke Shumaker <lukeshu@sbcglobal.net> | 2016-01-18 15:51:09 -0500 |
commit | 07891185449d9c400627d5ad088bfe65ae5ca817 (patch) | |
tree | cbfd17d468e0718f14a02b0c2fbb20d6681b33e4 /src/org | |
parent | b00bc94212488b2d1ef293765728e5b549fa8b5d (diff) |
stuff
Diffstat (limited to 'src/org')
-rw-r--r-- | src/org/usfirst/frc/team4272/robot2016/Teleop.java | 6 | ||||
-rw-r--r-- | src/org/usfirst/frc/team4272/robotlib/PIDController.java | 36 |
2 files changed, 21 insertions, 21 deletions
diff --git a/src/org/usfirst/frc/team4272/robot2016/Teleop.java b/src/org/usfirst/frc/team4272/robot2016/Teleop.java index 0238aac..4853162 100644 --- a/src/org/usfirst/frc/team4272/robot2016/Teleop.java +++ b/src/org/usfirst/frc/team4272/robot2016/Teleop.java @@ -2,7 +2,7 @@ package org.usfirst.frc.team4272.robot2016; import org.usfirst.frc.team4272.robotlib.PushButton; import org.usfirst.frc.team4272.robotlib.Xbox360Controller.Button; - +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj.Joystick; public class Teleop { @@ -25,12 +25,14 @@ public class Teleop { /* Ball intake/shooter */ if (oi.lStick.getTrigger()) { /* intake */ - control.fBall = control.bBall = -.6; + control.fBall = control.bBall = -SmartDashboard.getNumber("intakeSpeed"); } else if (oi.rStick.getTrigger()) { /* outtake */ control.fBall = 1; if (oi.rStick.getRawButton(3)) { control.bBall = 1; + } else { + control.bBall = 0; } } else { control.fBall = control.bBall = 0; diff --git a/src/org/usfirst/frc/team4272/robotlib/PIDController.java b/src/org/usfirst/frc/team4272/robotlib/PIDController.java index 965851d..6650ad4 100644 --- a/src/org/usfirst/frc/team4272/robotlib/PIDController.java +++ b/src/org/usfirst/frc/team4272/robotlib/PIDController.java @@ -34,7 +34,12 @@ import edu.wpi.first.wpilibj.SpeedController; //import edu.wpi.first.wpilibj.PIDController; /** - * TODO: Write JavaDocs + * A variant of edu.wpi.first.wpilibj.PIDController that also: + * <ul> + * <li> implements SpeedController (and therefore PIDOutput) + * <li> has auto-enable/disable functionality to avoid "locking" the + * motor when the setpoint is 0. + * * @author Luke Shumaker <lukeshu@sbcglobal.net> */ public class PIDController extends edu.wpi.first.wpilibj.PIDController implements SpeedController { @@ -47,37 +52,28 @@ public class PIDController extends edu.wpi.first.wpilibj.PIDController implement public final PIDSource source; public final PIDOutput output; - /* Mimic the four PIDController constructors *******************/ + /* Constructors *******************************************************/ public PIDController(double Kp, double Ki, double Kd, PIDSource source, PIDOutput output) { - super(Kp, Ki, Kd, source, output); - this.source = source; - this.output = output; + this(Kp, Ki, Kd, source, output, kDefaultPeriod, false); } public PIDController(double Kp, double Ki, double Kd, PIDSource source, PIDOutput output, double period) { - super(Kp, Ki, Kd, source, output, period); - this.source = source; - this.output = output; + this(Kp, Ki, Kd, source, output, period, false); } - public PIDController(double Kp, double Ki, double Kd, PIDSource source, PIDOutput output, boolean autodisable) { - super(Kp, Ki, Kd, source, output); - this.autodisable = autodisable; - enabled = this.isEnabled(); - this.source = source; - this.output = output; + this(Kp, Ki, Kd, source, output, kDefaultPeriod, autodisable); } public PIDController(double Kp, double Ki, double Kd, PIDSource source, PIDOutput output, double period, boolean autodisable) { super(Kp, Ki, Kd, source, output, period); this.autodisable = autodisable; - enabled = this.isEnabled(); + this.enabled = this.isEnabled(); this.source = source; this.output = output; } - /* Mimic the four PIDController constructors *******************/ + /* Mimic the four PIDController constructors **************************/ - public void setSetpoint(double output) { + public synchronized void setSetpoint(double output) { if ((output == 0) && autodisable) { disable(); enabled = false; @@ -90,12 +86,14 @@ public class PIDController extends edu.wpi.first.wpilibj.PIDController implement } } - /* Implement PIDOutput (a parent of SpeedController) */ + /* Implement PIDOutput (a parent of SpeedController) *******************/ + public void pidWrite(double output) { setSetpoint(output); } - /* Implement SpeedController */ + /* Implement SpeedController *******************************************/ + public void set(double output) { setSetpoint(output); } |