Skip to content

Commit

Permalink
Merge branch 'automation-tuning' into automations
Browse files Browse the repository at this point in the history
  • Loading branch information
srimanachanta committed Mar 16, 2024
2 parents 3623c26 + 781d203 commit 9838c87
Show file tree
Hide file tree
Showing 33 changed files with 1,101 additions and 929 deletions.
3 changes: 2 additions & 1 deletion build.gradle
Original file line number Diff line number Diff line change
@@ -1,8 +1,9 @@
plugins {
id "java"
id "edu.wpi.first.GradleRIO" version "2024.3.1"
id "edu.wpi.first.GradleRIO" version "2024.3.2"
id "com.peterabeles.gversion" version "1.10.2"
id "com.diffplug.spotless" version "6.24.0"
id "io.freefair.lombok" version "8.4"
}

java {
Expand Down
10 changes: 6 additions & 4 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -23,9 +23,11 @@ public void robotInit() {
// Set up data receivers & replay source
switch (Constants.getRobotMode()) {
case REAL:
// Running on a real robot, log to a USB stick
LoggerUtil.getLogPath()
.ifPresent(p -> Logger.addDataReceiver(new WPILOGWriter(p.toString())));
if (Constants.LOGGER_PARAMETERS.enableUSBLogging()) {
// Running on a real robot, log to a USB stick
LoggerUtil.getLogPath()
.ifPresent(p -> Logger.addDataReceiver(new WPILOGWriter(p.toString())));
}
Logger.addDataReceiver(new NT4Publisher());
break;
case SIM:
Expand All @@ -41,7 +43,7 @@ public void robotInit() {
break;
}

if (Constants.ENABLE_LOGGING) Logger.start();
if (Constants.LOGGER_PARAMETERS.enableLogger()) Logger.start();

if (Constants.getRobotMode() == Constants.RobotMode.SIM) {
DriverStation.silenceJoystickConnectionWarning(true);
Expand Down
107 changes: 45 additions & 62 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,23 +2,21 @@

import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine;
import frc.robot.commands.DriveTeleop;
import frc.robot.commands.ShooterTeleop;
import frc.robot.constants.Constants;
import frc.robot.oi.ControlsInterface;
import frc.robot.oi.SrimanXbox;
import frc.robot.oi.SingleXbox;
import frc.robot.subsystems.drive.*;
import frc.robot.subsystems.intake.*;
import frc.robot.subsystems.shooter.*;
import frc.robot.subsystems.shooter.dynamics.ShooterDynamics;
import frc.robot.subsystems.shooter.dynamics.ShooterState;
import frc.robot.subsystems.vision.*;
import frc.robot.util.PoseEstimator;
import java.util.Optional;
import org.littletonrobotics.junction.networktables.LoggedDashboardChooser;

public class RobotContainer {
private final ControlsInterface controlsInterface = new SrimanXbox();
private final ControlsInterface controlsInterface = new SingleXbox();

private final DriveBase m_drive;
private final ShooterBase m_shooter;
Expand Down Expand Up @@ -96,49 +94,8 @@ private void configureAutos() {

private void configureTunableParameters() {
m_autoChooser.addOption(
"DriveDynamicForward", m_drive.characterizeDriveDynamic(SysIdRoutine.Direction.kForward));
m_autoChooser.addOption(
"DriveDynamicReverse", m_drive.characterizeDriveDynamic(SysIdRoutine.Direction.kReverse));
m_autoChooser.addOption(
"DriveQuasistaticForward",
m_drive.characterizeDriveQuasistatic(SysIdRoutine.Direction.kForward));
m_autoChooser.addOption(
"DriveQuasistaticReverse",
m_drive.characterizeDriveQuasistatic(SysIdRoutine.Direction.kReverse));
m_autoChooser.addOption(
"ErectorDynamicForward",
m_shooter.characterizeErectorDynamic(SysIdRoutine.Direction.kForward));
m_autoChooser.addOption(
"ErectorDynamicReverse",
m_shooter.characterizeErectorDynamic(SysIdRoutine.Direction.kReverse));
m_autoChooser.addOption(
"ErectorQuasistaticForward",
m_shooter.characterizeErectorQuasistatic(SysIdRoutine.Direction.kForward));
m_autoChooser.addOption(
"ErectorQuasistaticReverse",
m_shooter.characterizeErectorQuasistatic(SysIdRoutine.Direction.kReverse));
m_autoChooser.addOption(
"ShooterDynamicForward",
m_shooter.characterizeShooterDynamic(SysIdRoutine.Direction.kForward));
m_autoChooser.addOption(
"ShooterDynamicReverse",
m_shooter.characterizeShooterDynamic(SysIdRoutine.Direction.kReverse));
m_autoChooser.addOption(
"ShooterQuasistaticForward",
m_shooter.characterizeShooterQuasistatic(SysIdRoutine.Direction.kForward));
m_autoChooser.addOption(
"ShooterQuasistaticReverse",
m_shooter.characterizeShooterQuasistatic(SysIdRoutine.Direction.kReverse));
m_autoChooser.addOption(
"WristDynamicForward", m_intake.characterizeWristDynamic(SysIdRoutine.Direction.kForward));
m_autoChooser.addOption(
"WristDynamicReverse", m_intake.characterizeWristDynamic(SysIdRoutine.Direction.kReverse));
m_autoChooser.addOption(
"WristQuasistaticForward",
m_intake.characterizeWristQuasistatic(SysIdRoutine.Direction.kForward));
m_autoChooser.addOption(
"WristQuasistaticReverse",
m_intake.characterizeWristQuasistatic(SysIdRoutine.Direction.kReverse));
"ShooterModuleFFCharacterization", m_shooter.getShooterCharacterizationCommand());
m_autoChooser.addOption("DriveFFCharacterization", m_drive.getDriveCharacterizationCommand());
}

private void configureButtonBindings() {
Expand All @@ -160,22 +117,48 @@ private void configureButtonBindings() {

controlsInterface.moduleLock().onTrue(Commands.runOnce(m_drive::stopWithX, m_drive));

// Drive teleop override button
controlsInterface
.trajectoryOverride()
.shoot()
.and(m_shooter::canShoot)
.onTrue(Commands.runOnce(() -> m_shooter.setKickupVoltage(12.0), m_shooter))
.onFalse(Commands.runOnce(() -> m_shooter.setKickupVoltage(0.0), m_shooter));

controlsInterface
.intake()
.and(() -> !m_shooter.holdingNote())
.onTrue(
Commands.runOnce(
() -> {
m_drive.getCurrentCommand().cancel();
m_drive.stop();
}));

m_shooter.setDefaultCommand(
new ShooterTeleop(
m_shooter,
() -> PoseEstimator.getInstance().getPose(),
m_drive::getVelocity,
controlsInterface));
Commands.sequence(
Commands.parallel(
Commands.runOnce(
() -> {
m_shooter.setAutoModeEnabled(false);
m_shooter.setSetpoint(ShooterState.GROUND_INTAKE_STATE);
},
m_shooter),
Commands.runOnce(
() -> m_intake.setWristGoal(Constants.Intake.GROUND_INTAKE_ANGLE),
m_intake)),
Commands.waitUntil(() -> m_shooter.atSetpoint() && m_intake.atWristGoal()),
Commands.run(
() -> {
m_intake.setRollersVoltage(12.0);
m_intake.setIndexerVoltage(12.0);
m_shooter.setKickupVoltage(8.0);
},
m_intake,
m_shooter)
.until(m_shooter::holdingNote),
Commands.waitSeconds(0.25),
Commands.runOnce(
() -> {
m_intake.setRollersVoltage(0);
m_intake.setIndexerVoltage(0);
m_shooter.setKickupVoltage(0);
m_intake.setWristGoal(Constants.Intake.STOW_ANGLE);
m_shooter.setAutoModeEnabled(true);
},
m_intake,
m_shooter)));
}

public Command getAutonomousCommand() {
Expand Down
24 changes: 12 additions & 12 deletions src/main/java/frc/robot/commands/DriveTeleop.java
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
import java.util.function.BiFunction;
import java.util.function.BooleanSupplier;
import java.util.function.DoubleSupplier;
import org.littletonrobotics.junction.Logger;

public class DriveTeleop extends Command {
private static final LoggedTunableNumber controllerDeadband =
Expand All @@ -40,14 +41,7 @@ public class DriveTeleop extends Command {

static {
switch (Constants.getRobotType()) {
case ROBOT_2024_COMP -> {
headingKp.initDefault(0.0); // TODO
headingKd.initDefault(0.0); // TODO
headingToleranceDegrees.initDefault(1.0);
headingMaxVelocityScalar.initDefault(0.8);
headingMaxAccelerationScalar.initDefault(0.8);
}
case ROBOT_SIMBOT -> {
case ROBOT_SIMBOT, ROBOT_2024_COMP -> {
headingKp.initDefault(5.0);
headingKd.initDefault(0.0);
headingToleranceDegrees.initDefault(1.0);
Expand Down Expand Up @@ -187,10 +181,16 @@ public void execute() {
headingSupplier
.apply(currentPose, driveBase.getVelocity())
.ifPresent(
v ->
speeds.omegaRadiansPerSecond =
headingController.calculate(
currentPose.getRotation().getRadians(), v.getRadians()));
v -> {
speeds.omegaRadiansPerSecond =
headingController.calculate(
currentPose.getRotation().getRadians(), v.getRadians());
Logger.recordOutput(
"TeleopDrive/HeadingControllerPose",
new Pose2d(currentPose.getTranslation(), v));
Logger.recordOutput(
"TeleopDrive/HeadingError", headingController.getPositionError());
});
}

driveBase.runVelocity(speeds);
Expand Down
103 changes: 103 additions & 0 deletions src/main/java/frc/robot/commands/FeedForwardCharacterization.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,103 @@
package frc.robot.commands;

import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Subsystem;
import frc.robot.util.PolynomialRegression;
import java.util.LinkedList;
import java.util.List;
import java.util.function.Consumer;
import java.util.function.Supplier;
import org.littletonrobotics.junction.Logger;

public class FeedForwardCharacterization extends Command {
private static final double START_DELAY_SECS = 2.0;

private FeedForwardCharacterizationData data;
private final String logKey;
private final Consumer<Double> voltageConsumer;
private final Supplier<Double> velocitySupplier;
private final double rampRateVoltsPerSecond;
private final double timeout;

private final Timer timer = new Timer();

public FeedForwardCharacterization(
Subsystem subsystem,
String mechanismName,
Consumer<Double> voltageConsumer,
Supplier<Double> velocitySupplier,
double rampRateVoltsPerSecond,
double timeout) {
addRequirements(subsystem);
this.logKey = subsystem.getName() + "/" + mechanismName;
this.voltageConsumer = voltageConsumer;
this.velocitySupplier = velocitySupplier;
this.rampRateVoltsPerSecond = rampRateVoltsPerSecond;
this.timeout = timeout;
}

@Override
public void initialize() {
data = new FeedForwardCharacterizationData(logKey);
timer.restart();
}

@Override
public void execute() {
if (timer.get() < START_DELAY_SECS) {
voltageConsumer.accept(0.0);
} else {
double voltage = (timer.get() - START_DELAY_SECS) * rampRateVoltsPerSecond;
voltageConsumer.accept(voltage);
data.add(velocitySupplier.get(), voltage);
}
}

@Override
public void end(boolean interrupted) {
voltageConsumer.accept(0.0);
timer.stop();
data.calculateAndLogResults();
}

@Override
public boolean isFinished() {
return timer.get() >= timeout + START_DELAY_SECS;
}

public static class FeedForwardCharacterizationData {
private static final String LOG_KEY_BASE = "FeedForwardCharacterizationResults";
private final String logKey;
private final List<Double> velocityData = new LinkedList<>();
private final List<Double> voltageData = new LinkedList<>();

public FeedForwardCharacterizationData(String logKey) {
this.logKey = LOG_KEY_BASE + "/" + logKey;
}

public void add(double velocity, double voltage) {
if (Math.abs(velocity) > 1E-4) {
velocityData.add(Math.abs(velocity));
voltageData.add(Math.abs(voltage));
}
}

public void calculateAndLogResults() {
if (velocityData.isEmpty() || voltageData.isEmpty()) {
return;
}

PolynomialRegression regression =
new PolynomialRegression(
velocityData.stream().mapToDouble(Double::doubleValue).toArray(),
voltageData.stream().mapToDouble(Double::doubleValue).toArray(),
1);

Logger.recordOutput(logKey + "/SampleCount", velocityData.size());
Logger.recordOutput(logKey + "/R^2", regression.R2());
Logger.recordOutput(logKey + "/kS", regression.beta(0));
Logger.recordOutput(logKey + "/kV", regression.beta(1));
}
}
}
Loading

0 comments on commit 9838c87

Please sign in to comment.