-
Notifications
You must be signed in to change notification settings - Fork 0
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
* need to find out pose of robot and rdius of drive base * done, but math is probs wrong and idk where to call the command * added to robot container * Use real-world values and correctly grab data * Update drive wheel radius --------- Co-authored-by: charlesmackenzie <[email protected]>
- Loading branch information
1 parent
fb9cff4
commit 01a584d
Showing
4 changed files
with
123 additions
and
7 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
89 changes: 89 additions & 0 deletions
89
src/main/java/frc/robot/commands/WheelRadiusCharacterization.java
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,89 @@ | ||
package frc.robot.commands; | ||
|
||
import edu.wpi.first.math.MathUtil; | ||
import edu.wpi.first.math.filter.SlewRateLimiter; | ||
import edu.wpi.first.math.kinematics.ChassisSpeeds; | ||
import edu.wpi.first.math.util.Units; | ||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; | ||
import edu.wpi.first.wpilibj2.command.Command; | ||
import frc.robot.Constants.TunerConstants; | ||
import frc.robot.subsystems.drive.CommandSwerveDrivetrain; | ||
import java.util.function.DoubleSupplier; | ||
|
||
public class WheelRadiusCharacterization extends Command { | ||
private static final double characterizationSpeed = 0.8; | ||
private static final double driveRadius = TunerConstants.kModuleRadiusMeters; | ||
|
||
private final DoubleSupplier gyroYawRadsSupplier; // need to get pose of the robot | ||
private final CommandSwerveDrivetrain drivetrain; | ||
private final SlewRateLimiter omegaLimiter = new SlewRateLimiter(1.0); | ||
|
||
private double lastGyroYawRads = 0.0; | ||
private double accumGyroYawRads = 0.0; | ||
|
||
private double omegaDirection = 1; | ||
|
||
private double[] startWheelPositions; | ||
|
||
private double currentEffectiveWheelRadius = 0.0; | ||
|
||
public WheelRadiusCharacterization( | ||
CommandSwerveDrivetrain drive, DoubleSupplier gyroYawRadsSupplier) { | ||
drivetrain = drive; | ||
this.gyroYawRadsSupplier = gyroYawRadsSupplier; | ||
addRequirements(drive); | ||
} | ||
|
||
@Override | ||
public void initialize() { | ||
// Reset | ||
lastGyroYawRads = gyroYawRadsSupplier.getAsDouble(); | ||
accumGyroYawRads = 0.0; | ||
|
||
startWheelPositions = drivetrain.getWheelRadiusCharacterizationPosition(); | ||
|
||
omegaLimiter.reset(0); | ||
|
||
if (!SmartDashboard.containsKey("Effective Wheel Radius")) { | ||
SmartDashboard.putNumber("Effective Wheel Radius", 0.0); | ||
} | ||
} | ||
|
||
@Override | ||
public void execute() { | ||
// Run drive at velocity | ||
drivetrain.runWheelRadiusCharacterization( | ||
omegaLimiter.calculate(omegaDirection * characterizationSpeed)); | ||
|
||
// Get yaw and wheel positions | ||
accumGyroYawRads += | ||
MathUtil.angleModulus(gyroYawRadsSupplier.getAsDouble() - lastGyroYawRads); | ||
lastGyroYawRads = gyroYawRadsSupplier.getAsDouble(); | ||
double averageWheelPosition = 0.0; | ||
double[] wheelPositions = drivetrain.getWheelRadiusCharacterizationPosition(); | ||
for (int i = 0; i < 4; i++) { | ||
averageWheelPosition += Math.abs(wheelPositions[i] - startWheelPositions[i]); | ||
} | ||
averageWheelPosition /= 4.0; | ||
|
||
currentEffectiveWheelRadius = (accumGyroYawRads * driveRadius) / averageWheelPosition; | ||
SmartDashboard.putNumber( | ||
"TestMode/RadiusCharacterization/DrivePosition", averageWheelPosition); | ||
SmartDashboard.putNumber( | ||
"TestMode/RadiusCharacterization/AccumGyroYawRads", accumGyroYawRads); | ||
SmartDashboard.putNumber( | ||
"TestMode/RadiusCharacterization/CurrentWheelRadiusInches", | ||
Units.metersToInches(currentEffectiveWheelRadius)); | ||
} | ||
|
||
@Override | ||
public void end(boolean interrupted) { | ||
if (Math.abs(accumGyroYawRads) <= Math.PI * 2.0) { | ||
SmartDashboard.putNumber("Effective Wheel Radius", -1.0); | ||
} else { | ||
SmartDashboard.putNumber("Effective Wheel Radius", currentEffectiveWheelRadius); | ||
} | ||
|
||
drivetrain.setGoalChassisSpeeds(new ChassisSpeeds()); | ||
} | ||
} |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters