Skip to content

Commit 2c604e3

Browse files
calculate robotperiod
1 parent f927678 commit 2c604e3

3 files changed

Lines changed: 27 additions & 11 deletions

File tree

build.gradle

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -79,7 +79,7 @@ dependencies {
7979
simulationRelease wpi.sim.enableRelease()
8080

8181
testImplementation 'org.junit.jupiter:junit-jupiter:5.10.1'
82-
implementation "com.github.deepbluerobotics:lib199:3dc0356f5ea971aa24802980371effc7fc2215fc"
82+
implementation "com.github.deepbluerobotics:lib199:cc93080eab462da161d0d47eda253ac8b31495ee"
8383
}
8484

8585
test {

src/main/java/org/carlmontrobotics/Constants.java

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -40,7 +40,7 @@ public static final class Drivetrain {
4040

4141
public static final double driveModifier = 1;
4242
public static final double wheelDiameterMeters = Units.inchesToMeters(4.0) * 7.36/7.65 /* empirical correction */;
43-
public static final double mu = 0.5; /* 70/83.2; */
43+
public static final double mu = 1; /* 70/83.2; */
4444

4545
public static final double NEOFreeSpeed = 5676 * (2 * Math.PI) / 60; // radians/s
4646
// Angular speed to translational speed --> v = omega * r / gearing
@@ -81,7 +81,7 @@ public static final class Drivetrain {
8181
// Forward: 1.72, 1.71, 1.92, 1.94
8282
// Backward: 1.92, 1.92, 2.11, 1.89
8383
// Order of modules: (FL, FR, BL, BR)
84-
public static final double[] drivekP = {4.5, 4.5, 4.5, 3.5}; //{1.82/100, 1.815/100, 2.015/100, 1.915/100};
84+
public static final double[] drivekP = {2.8, 2.8, 2.8, 2.8}; //{1.82/100, 1.815/100, 2.015/100, 1.915/100};
8585
public static final double[] drivekI = {0, 0, 0, 0};
8686
public static final double[] drivekD = {0, 0, 0, 0};
8787
public static final boolean[] driveInversion = {false, false, false, false};
@@ -136,11 +136,11 @@ public static final class Drivetrain {
136136

137137
//#region Command Constants
138138

139-
public static final double kNormalDriveSpeed = 1; // Percent Multiplier
140-
public static final double kNormalDriveRotation = 0.5; // Percent Multiplier
141-
public static final double kSlowDriveSpeed = 0.4; // Percent Multiplier
142-
public static final double kSlowDriveRotation = 0.250; // Percent Multiplier
143-
public static final double kAlignMultiplier = 1D/3D;
139+
public static double kNormalDriveSpeed = 1; // Percent Multiplier
140+
public static double kNormalDriveRotation = 0.5; // Percent Multiplier
141+
public static double kSlowDriveSpeed = 0.4; // Percent Multiplier
142+
public static double kSlowDriveRotation = 0.250; // Percent Multiplier
143+
public static double kAlignMultiplier = 1D/3D;
144144
public static final double kAlignForward = 0.6;
145145

146146
public static final double wheelTurnDriveSpeed = 0.0001; // Meters / Second ; A non-zero speed just used to orient the wheels to the correct angle. This should be very small to avoid actually moving the robot.

src/main/java/org/carlmontrobotics/commands/TeleopDrive.java

Lines changed: 19 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -11,19 +11,21 @@
1111

1212
import edu.wpi.first.math.geometry.Rotation2d;
1313
import edu.wpi.first.math.geometry.Translation2d;
14+
import edu.wpi.first.wpilibj.Timer;
1415
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
1516
import edu.wpi.first.wpilibj2.command.Command;
1617

1718
public 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

Comments
 (0)