1111
1212import edu .wpi .first .math .geometry .Rotation2d ;
1313import edu .wpi .first .math .geometry .Translation2d ;
14+ import edu .wpi .first .wpilibj .Timer ;
1415import edu .wpi .first .wpilibj .smartdashboard .SmartDashboard ;
1516import edu .wpi .first .wpilibj2 .command .Command ;
1617
1718public class TeleopDrive extends Command {
1819
19- private static final double robotPeriod = Robot .robot .getPeriod ();
20+ private static double robotPeriod = Robot .robot .getPeriod ();
2021 private final Drivetrain drivetrain ;
2122 private DoubleSupplier fwd ;
2223 private DoubleSupplier str ;
2324 private DoubleSupplier rcw ;
2425 private BooleanSupplier slow ;
2526 private double currentForwardVel = 0 ;
2627 private double currentStrafeVel = 0 ;
28+ private double prevTimestamp ;
2729
2830 /**
2931 * Creates a new TeleopDrive.
@@ -39,12 +41,26 @@ public TeleopDrive(Drivetrain drivetrain, DoubleSupplier fwd, DoubleSupplier str
3941 // Called when the command is initially scheduled.
4042 @ Override
4143 public void initialize () {
44+ SmartDashboard .putNumber ("slow turn const" , kSlowDriveRotation );
45+ SmartDashboard .putNumber ("slow speed const" , kSlowDriveSpeed );
46+ SmartDashboard .putNumber ("normal turn const" , kNormalDriveRotation );
47+ SmartDashboard .putNumber ("normal speed const" , kNormalDriveSpeed );
48+ prevTimestamp = Timer .getFPGATimestamp ();
4249 }
4350
4451 // Called every time the scheduler runs while the command is scheduled.
4552 @ Override
4653 public void execute () {
4754 double [] speeds = getRequestedSpeeds ();
55+ double currentTime = Timer .getFPGATimestamp ();
56+ robotPeriod = currentTime - prevTimestamp ;
57+ SmartDashboard .putNumber ("Elapsed time" , currentTime - prevTimestamp );
58+ prevTimestamp = currentTime ;
59+ kSlowDriveRotation = SmartDashboard .getNumber ("slow turn const" , kSlowDriveRotation );
60+ kSlowDriveSpeed = SmartDashboard .getNumber ("slow speed const" , kSlowDriveSpeed );
61+ kNormalDriveRotation = SmartDashboard .getNumber ("normal turn const" , kNormalDriveRotation );
62+ kNormalDriveSpeed = SmartDashboard .getNumber ("normal speed const" , kNormalDriveSpeed );
63+
4864
4965 SmartDashboard .putNumber ("fwd" , speeds [0 ]);
5066 SmartDashboard .putNumber ("strafe" , speeds [1 ]);
@@ -88,9 +104,9 @@ public double[] getRequestedSpeeds() {
88104 currentForwardVel = forward ;
89105 currentStrafeVel = strafe ;
90106 }
91-
92107 // ATM, there is no rotational acceleration limit
93-
108+ // currentForwardVel = forward;
109+ // currentStrafeVel = strafe;
94110 // If the above math works, no velocity should be greater than the max velocity, so we don't need to limit it.
95111
96112 return new double [] {currentForwardVel , currentStrafeVel , -rotateClockwise };
0 commit comments