Skip to content

Commit

Permalink
Wheel characterization (#158)
Browse files Browse the repository at this point in the history
* 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
AlexEvergarden and charlesmackenzie authored Mar 11, 2024
1 parent fb9cff4 commit 01a584d
Show file tree
Hide file tree
Showing 4 changed files with 123 additions and 7 deletions.
13 changes: 8 additions & 5 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -47,11 +47,11 @@ public static enum Mode {
}

public static final class FeatureFlags {
public static final boolean runVision = true;
public static final boolean runVision = false;

public static final boolean runIntake = true;
public static final boolean runScoring = true;
public static final boolean runEndgame = true;
public static final boolean runIntake = false;
public static final boolean runScoring = false;
public static final boolean runEndgame = false;
public static final boolean runDrive = true;

public static final boolean enableLEDS = false;
Expand Down Expand Up @@ -310,7 +310,7 @@ public static final class TunerConstants {

private static final double kDriveGearRatio = 6.122448979591837;
private static final double kSteerGearRatio = 21.428571428571427;
private static final double kWheelRadiusInches = 2;
private static final double kWheelRadiusInches = 1.925;

private static final boolean kSteerMotorReversed = true;
private static final boolean kInvertLeftSide = false;
Expand Down Expand Up @@ -386,6 +386,9 @@ public static final class TunerConstants {
private static final double kFrontLeftXPosInches = -10.375;
private static final double kFrontLeftYPosInches = -10.375;

public static final double kModuleRadiusMeters =
Units.inchesToMeters(Math.hypot(kFrontLeftXPosInches, kFrontLeftYPosInches));

private static final SwerveModuleConstants FrontLeft =
ConstantCreator.createModuleConstants(
kFrontLeftSteerMotorId,
Expand Down
15 changes: 13 additions & 2 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@
import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.button.CommandJoystick;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import frc.robot.Constants.ConversionConstants;
import frc.robot.Constants.DriveConstants;
import frc.robot.Constants.EndgameConstants;
import frc.robot.Constants.FeatureFlags;
Expand All @@ -24,6 +25,7 @@
import frc.robot.Constants.VisionConstants;
import frc.robot.commands.DriveWithJoysticks;
import frc.robot.commands.ShootWithGamepad;
import frc.robot.commands.WheelRadiusCharacterization;
import frc.robot.subsystems.LED;
import frc.robot.subsystems.drive.CommandSwerveDrivetrain;
import frc.robot.subsystems.drive.CommandSwerveDrivetrain.AlignState;
Expand Down Expand Up @@ -329,6 +331,7 @@ private void configureModes() {
testModeChooser.addOption("Hood Tuning", "tuning-hood");
testModeChooser.addOption("Shooter Tuning", "tuning-shooter");
testModeChooser.addOption("Endgame Tuning", "tuning-endgame");
testModeChooser.addOption("Wheel Characterization", "characterization-wheel");

SmartDashboard.putData("Test Mode Chooser", testModeChooser);
}
Expand Down Expand Up @@ -647,10 +650,18 @@ public void testInit() {
endgameSubsystem.setVolts(0, 0);
endgameSubsystem.setAction(EndgameAction.OVERRIDE);
}));
break;
break;
case "characterization-wheel":
controller.a()
.whileTrue(
new WheelRadiusCharacterization(
drivetrain,
() -> drivetrain.getPigeon2().getYaw().getValueAsDouble()
* ConversionConstants.kDegreesToRadians));
break;
}
}
// spotless:on
}

public void testPeriodic() {}

Expand Down
89 changes: 89 additions & 0 deletions src/main/java/frc/robot/commands/WheelRadiusCharacterization.java
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());
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -472,6 +472,19 @@ public boolean isAligned() {
return Math.abs(alignError) < DriveConstants.alignToleranceRadians;
}

public void runWheelRadiusCharacterization(double speed) {
setGoalChassisSpeeds(new ChassisSpeeds(0, 0, speed));
}

public double[] getWheelRadiusCharacterizationPosition() {
return new double[] {
this.getModule(0).getDriveMotor().getPosition().getValueAsDouble(),
this.getModule(1).getDriveMotor().getPosition().getValueAsDouble(),
this.getModule(2).getDriveMotor().getPosition().getValueAsDouble(),
this.getModule(3).getDriveMotor().getPosition().getValueAsDouble()
};
}

@Override
public void periodic() {
controlDrivetrain();
Expand Down

0 comments on commit 01a584d

Please sign in to comment.