99import edu .wpi .first .wpilibj .PIDOutput ;
1010import edu .wpi .first .wpilibj .PIDSource ;
1111import edu .wpi .first .wpilibj .command .Command ;
12+ import edu .wpi .first .wpilibj .smartdashboard .SmartDashboard ;
1213
1314/**
1415 * Drives the robot a certain target distance using PID. Implements PIDOutput in
@@ -20,9 +21,6 @@ public class PIDMove extends Command implements PIDOutput {
2021 private DrivetrainInterface dt ;
2122 private PIDController moveController ;
2223 private PIDSource avg ;
23- private SmartDashboardInterface sd ;
24- private double pointX ;
25- private double pointY ;
2624
2725 /**
2826 * Constructs this command with a new PIDController. Sets all of the
@@ -45,14 +43,13 @@ public PIDMove(double targ, DrivetrainInterface dt, SmartDashboardInterface sd,
4543 target = targ ;
4644 this .dt = dt ;
4745 this .avg = avg ;
48- this .sd = sd ;
4946 if (Robot .dt != null ) {
5047 requires (Robot .dt );
5148 }
5249 double kf = 1 / (dt .getCurrentMaxSpeed () * sd .getConst ("Default PID Update Time" , 0.05 ));
5350 moveController = new PIDController (sd .getConst ("MovekP" , 0.1 ), sd .getConst ("MovekI" , 0 ),
5451 sd .getConst ("MovekD" , 0 ), kf , avg , this );
55- sd .putData ("Move PID" , moveController );
52+ SmartDashboard .putData ("Move PID" , moveController );
5653 }
5754
5855 /**
@@ -73,19 +70,20 @@ public PIDMove(double targ, DrivetrainInterface dt, SmartDashboardInterface sd,
7370 * the PIDSorceAverage of the DT's two Encoders
7471 */
7572 public PIDMove (double [] point , DrivetrainInterface dt , SmartDashboardInterface sd , PIDSource avg ) {
76- pointX = point [0 ];
77- pointY = point [1 ];
73+ double dx = point [0 ] - AutoUtils . position . getX () ;
74+ double dy = point [1 ] - AutoUtils . position . getY () ;
7875
76+ double dist = Math .sqrt (dx * dx + dy * dy ); // pythagorean theorem to find distance
77+
78+ this .target = dist ;
7979 this .dt = dt ;
8080 this .avg = avg ;
81- this .sd = sd ;
8281 if (Robot .dt != null ) {
8382 requires (Robot .dt );
8483 }
8584 double kf = 1 / (dt .getCurrentMaxSpeed () * sd .getConst ("Default PID Update Time" , 0.05 ));
8685 moveController = new PIDController (sd .getConst ("MovekP" , 1 ), sd .getConst ("MovekI" , 0 ), sd .getConst ("MovekD" , 0 ),
8786 kf , avg , this );
88- sd .putData ("Move PID" , moveController );
8987 }
9088
9189 /**
@@ -94,12 +92,6 @@ public PIDMove(double[] point, DrivetrainInterface dt, SmartDashboardInterface s
9492 */
9593 @ Override
9694 public void initialize () {
97- double dx = pointX - AutoUtils .position .getX ();
98- double dy = pointY - AutoUtils .position .getY ();
99-
100- double dist = Math .sqrt (dx * dx + dy * dy ); // pythagorean theorem to find distance
101- this .target = dist ;
102-
10395 dt .resetDistEncs ();
10496 moveController .disable ();
10597 // input is in inches
@@ -108,7 +100,6 @@ public void initialize() {
108100 moveController .setOutputRange (-1.0 , 1.0 );
109101 moveController .setContinuous (false );
110102 moveController .setAbsoluteTolerance (Robot .getConst ("MoveTolerance" , 0.1 ));
111- System .out .println ("move target = " + target );
112103 moveController .setSetpoint (target );
113104
114105 moveController .enable ();
@@ -123,8 +114,8 @@ public void initialize() {
123114 @ Override
124115 protected void execute () {
125116 System .out .println ("Enc Avg Dist: " + avg .pidGet ());
126- sd .putNumber ("Move PID Result" , moveController .get ());
127- sd .putNumber ("Move PID Error" , moveController .getError ());
117+ SmartDashboard .putNumber ("Move PID Result" , moveController .get ());
118+ SmartDashboard .putNumber ("Move PID Error" , moveController .getError ());
128119 }
129120
130121 /**
@@ -182,6 +173,6 @@ protected void interrupted() {
182173 @ Override
183174 public void pidWrite (double output ) {
184175 dt .arcadeDrive (output , 0 );
185- sd .putNumber ("Move PID Output" , output );
176+ SmartDashboard .putNumber ("Move PID Output" , output );
186177 }
187178}
0 commit comments