diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 47ab6960..ea5b9938 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -101,6 +101,7 @@ private DriveConstants() { ); } + public static class ShooterConstants { private ShooterConstants() { throw new IllegalStateException("Static classes should not be constructed"); @@ -122,4 +123,24 @@ private ShooterConstants() { public static final boolean BOTTOM_RIGHT_INVERTED = false; public static final boolean KICKER_INVERTED = true; } + + public class ClimberConstants { + private ClimberConstants() { + throw new IllegalStateException("Static class should not be constructed"); + } + + public static final int LEFT_CLIMBER_ID = 18; + public static final int RIGHT_CLIMBER_ID = 19; + + public static final double CLIMBER_KP = 0.0; + public static final double CLIMBER_KI = 0.0; + public static final double CLIMBER_KD = 0.0; + + public static final double CLIMBER_KV = 0.0; + public static final double CLIMBER_KS = 0.0; + public static final double CLIMBER_KA = 0.0; + + public static final double CLIMBER_GEAR_RATIO = 0.0; + public static final double CLIMBER_CONVERSION_FACTOR_INCHES = 0.0; + } } diff --git a/src/main/java/frc/robot/subsystems/climber/ClimberIO.java b/src/main/java/frc/robot/subsystems/climber/ClimberIO.java index 53ce7717..380f0b0b 100644 --- a/src/main/java/frc/robot/subsystems/climber/ClimberIO.java +++ b/src/main/java/frc/robot/subsystems/climber/ClimberIO.java @@ -1,7 +1,105 @@ package frc.robot.subsystems.climber; +import org.littletonrobotics.junction.AutoLog; + public interface ClimberIO { + @AutoLog + class ClimberIOInputs { + protected double leftClimberPosition = 0.0; + protected double rightClimberPosition = 0.0; + protected double leftClimberVelocity = 0.0; + protected double rightClimberVelocity = 0.0; + protected double leftClimberCurrentDraw = 0.0; + protected double rightClimberCurrentDraw = 0.0; + protected double leftClimberCurrentSetpoint = 0.0; + protected double rightClimberCurrentSetpoint = 0.0; + protected double leftClimberAppliedOutput = 0.0; + protected double rightClimberAppliedOutput = 0.0; + + public double getLeftClimberPosition() { + return leftClimberPosition; + } + + public void setLeftClimberPosition(double leftClimberPosition) { + this.leftClimberPosition = leftClimberPosition; + } + + public double getRightClimberPosition() { + return rightClimberPosition; + } + + public void setRightClimberPosition(double rightClimberPosition) { + this.rightClimberPosition = rightClimberPosition; + } + + public double getLeftClimberVelocity() { + return leftClimberVelocity; + } + + public void setLeftClimberVelocity(double leftClimberVelocity) { + this.leftClimberVelocity = leftClimberVelocity; + } + + public double getRightClimberVelocity() { + return rightClimberVelocity; + } + + public void setRightClimberVelocity(double rightClimberVelocity) { + this.rightClimberVelocity = rightClimberVelocity; + } + + public double getLeftClimberCurrentDraw() { + return leftClimberCurrentDraw; + } + + public void setLeftClimberCurrentDraw(double leftClimberCurrentDraw) { + this.leftClimberCurrentDraw = leftClimberCurrentDraw; + } + + public double getRightClimberCurrentDraw() { + return rightClimberCurrentDraw; + } + + public void setRightClimberCurrentDraw(double rightClimberCurrentDraw) { + this.rightClimberCurrentDraw = rightClimberCurrentDraw; + } + + public double getLeftClimberCurrentSetpoint() { + return leftClimberCurrentSetpoint; + } + + public void setLeftClimberCurrentSetpoint(double leftClimberCurrentSetpoint) { + this.leftClimberCurrentSetpoint = leftClimberCurrentSetpoint; + } + + public double getRightClimberCurrentSetpoint() { + return rightClimberCurrentSetpoint; + } + + public void setRightClimberCurrentSetpoint(double rightClimberCurrentSetpoint) { + this.rightClimberCurrentSetpoint = rightClimberCurrentSetpoint; + } + + public double getLeftClimberAppliedOutput() { + return leftClimberAppliedOutput; + } + + public void setLeftClimberAppliedOutput(double leftClimberAppliedOutput) { + this.leftClimberAppliedOutput = leftClimberAppliedOutput; + } + + public double getRightClimberAppliedOutput() { + return rightClimberAppliedOutput; + } + + public void setRightClimberAppliedOutput(double rightClimberAppliedOutput) { + this.rightClimberAppliedOutput = rightClimberAppliedOutput; + } + } - default void setLeftVoltage(double voltage) {} - default void setRightVoltage(double voltage) {} + default void setRightVoltage(double volts) {} + default void setLeftVoltage(double volts) {} + default void setRightPosition(double degrees) {} + default void setLeftPosition(double degrees) {} + default void updateInputs(ClimberIOInputsAutoLogged inputs) {} } diff --git a/src/main/java/frc/robot/subsystems/climber/ClimberIOPrototype.java b/src/main/java/frc/robot/subsystems/climber/ClimberIOPrototype.java index 416d599e..2330b0e3 100644 --- a/src/main/java/frc/robot/subsystems/climber/ClimberIOPrototype.java +++ b/src/main/java/frc/robot/subsystems/climber/ClimberIOPrototype.java @@ -1,36 +1,88 @@ package frc.robot.subsystems.climber; import com.ctre.phoenix6.configs.TalonFXConfiguration; -import com.ctre.phoenix6.controls.VoltageOut; +import com.ctre.phoenix6.controls.PositionVoltage; import com.ctre.phoenix6.hardware.TalonFX; import com.ctre.phoenix6.signals.InvertedValue; -import edu.wpi.first.math.MathUtil; +import frc.robot.Constants.ClimberConstants; +import lib.properties.phoenix6.Phoenix6PidPropertyBuilder; +import lib.properties.phoenix6.PidPropertyPublic; public class ClimberIOPrototype implements ClimberIO { - private final TalonFX m_leftTalon; - private final TalonFX m_rightTalon; - - public ClimberIOPrototype() { - m_leftTalon = new TalonFX(18); - m_rightTalon = new TalonFX(19); - - var rightTalonConfig = new TalonFXConfiguration(); - rightTalonConfig.MotorOutput.Inverted = InvertedValue.Clockwise_Positive; - m_rightTalon.getConfigurator().apply(rightTalonConfig); - - var leftTalonConfig = new TalonFXConfiguration(); - m_leftTalon.getConfigurator().apply(leftTalonConfig); - } - - @Override - public void setRightVoltage(double voltage) { - double clampedVoltage = MathUtil.clamp(voltage, -12, 12); - m_rightTalon.setVoltage(clampedVoltage); - } - - @Override - public void setLeftVoltage(double voltage) { - double clampedVoltage = MathUtil.clamp(voltage, -12, 12); - m_leftTalon.setVoltage(clampedVoltage); - } + private final TalonFX m_leftTalon; + private final TalonFX m_rightTalon; + private final PidPropertyPublic m_leftClimberPid; + private final PidPropertyPublic m_rightClimberPid; + + public ClimberIOPrototype() { + m_leftTalon = new TalonFX(ClimberConstants.LEFT_CLIMBER_ID); + m_rightTalon = new TalonFX(ClimberConstants.RIGHT_CLIMBER_ID); + + var rightTalonConfig = new TalonFXConfiguration(); + rightTalonConfig.MotorOutput.Inverted = InvertedValue.Clockwise_Positive; + m_rightTalon.getConfigurator().apply(rightTalonConfig); + + var leftTalonConfig = new TalonFXConfiguration(); + m_leftTalon.getConfigurator().apply(leftTalonConfig); + + m_leftClimberPid = new Phoenix6PidPropertyBuilder( + "Climber/Left PID", + false, m_leftTalon, 0) + .addP(ClimberConstants.CLIMBER_KP) + .addI(ClimberConstants.CLIMBER_KI) + .addD(ClimberConstants.CLIMBER_KD) + .build(); + + m_rightClimberPid = new Phoenix6PidPropertyBuilder( + "Climber/Right PID", + false, m_rightTalon, 0) + .addP(ClimberConstants.CLIMBER_KP) + .addI(ClimberConstants.CLIMBER_KI) + .addD(ClimberConstants.CLIMBER_KD) + .build(); + + } + + @Override + public void setLeftVoltage(double volts) { + m_leftTalon.setVoltage(volts); + } + + @Override + public void setRightVoltage(double volts) { + m_rightTalon.setVoltage(volts); + } + + @Override + public void setLeftPosition(double degrees) { + final PositionVoltage request = new PositionVoltage(0).withSlot(0); + m_leftTalon.setControl(request.withPosition(degrees / 360.0)); + } + + @Override + public void setRightPosition(double degrees) { + final PositionVoltage request = new PositionVoltage(0).withSlot(0); + m_rightTalon.setControl(request.withPosition(degrees / 360.0)); + } + + @Override + public void updateInputs(ClimberIOInputsAutoLogged inputs) { + m_leftClimberPid.updateIfChanged(); + m_rightClimberPid.updateIfChanged(); + + inputs.setLeftClimberPosition(m_leftTalon.getPosition().getValueAsDouble()); + inputs.setRightClimberPosition(m_rightTalon.getPosition().getValueAsDouble()); + + inputs.setLeftClimberVelocity(m_leftTalon.getVelocity().getValueAsDouble()); + inputs.setRightClimberVelocity(m_rightTalon.getVelocity().getValueAsDouble()); + + inputs.setLeftClimberCurrentDraw(m_leftTalon.getSupplyCurrent().getValueAsDouble()); + inputs.setRightClimberCurrentDraw(m_rightTalon.getSupplyCurrent().getValueAsDouble()); + + inputs.setLeftClimberCurrentSetpoint(m_leftTalon.getClosedLoopReference().getValueAsDouble()); + inputs.setRightClimberCurrentSetpoint(m_rightTalon.getClosedLoopReference().getValueAsDouble()); + + inputs.setLeftClimberAppliedOutput(m_leftTalon.getBridgeOutput().getValueAsDouble()); + inputs.setRightClimberAppliedOutput(m_rightTalon.getBridgeOutput().getValueAsDouble()); + } } diff --git a/src/main/java/frc/robot/subsystems/climber/ClimberSubsystem.java b/src/main/java/frc/robot/subsystems/climber/ClimberSubsystem.java index 03e291a9..2797da39 100644 --- a/src/main/java/frc/robot/subsystems/climber/ClimberSubsystem.java +++ b/src/main/java/frc/robot/subsystems/climber/ClimberSubsystem.java @@ -3,20 +3,29 @@ import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.SubsystemBase; +import org.littletonrobotics.junction.Logger; public class ClimberSubsystem extends SubsystemBase { - private final ClimberIO m_io; - public ClimberSubsystem(ClimberIO io) { - m_io = io; - } + private final ClimberIO m_io; + private final ClimberIOInputsAutoLogged m_inputs; + public ClimberSubsystem(ClimberIO io) { + m_io = io; + m_inputs = new ClimberIOInputsAutoLogged(); + } - public void setClimberPower(double power) { - m_io.setLeftVoltage(power * 12.0); - m_io.setRightVoltage(power * 12.0); - } + @Override + public void periodic() { + m_io.updateInputs(m_inputs); + Logger.processInputs("Climber", m_inputs); + } - public Command setClimberPowerFactory(double power) { - return run(() -> setClimberPower(power)); - } + public void setClimberPower(double power) { + m_io.setRightVoltage(power * 12.0); + m_io.setLeftVoltage(power * 12.0); + } + + public Command setClimberPowerFactory(double power) { + return run(() -> setClimberPower(power)); + } } diff --git a/src/main/java/frc/robot/subsystems/drive/module/Module.java b/src/main/java/frc/robot/subsystems/drive/module/Module.java index bc03ec63..a61511fa 100644 --- a/src/main/java/frc/robot/subsystems/drive/module/Module.java +++ b/src/main/java/frc/robot/subsystems/drive/module/Module.java @@ -90,7 +90,7 @@ public void periodic() { // Run closed loop turn control if (m_angleSetpoint != null) { - m_io.setTurnVoltage( + m_io.setTurnPositionDegs( m_turnFeedback.calculate(getAngle().getRadians(), m_angleSetpoint.getRadians())); // Run closed loop drive control @@ -105,7 +105,7 @@ public void periodic() { // Run drive controller double velocityRadPerSec = adjustSpeedSetpoint / WHEEL_RADIUS; - m_io.setDriveVoltage( + m_io.setDriveVelocityMPS( m_driveFeedforward.calculate(velocityRadPerSec) + m_driveFeedback.calculate(m_inputs.getDriveVelocityRadPerSec(), velocityRadPerSec)); } @@ -144,14 +144,14 @@ public void runCharacterization(double volts) { m_angleSetpoint = new Rotation2d(); // Open loop drive control - m_io.setDriveVoltage(volts); + m_io.setDriveVelocityMPS(volts); m_speedSetpoint = null; } /** Disables all outputs to motors. */ public void stop() { - m_io.setTurnVoltage(0.0); - m_io.setDriveVoltage(0.0); + m_io.setTurnPositionDegs(0.0); + m_io.setDriveVelocityMPS(0.0); // Disable closed loop control for turn and drive m_angleSetpoint = null; diff --git a/src/main/java/frc/robot/subsystems/drive/module/ModuleIO.java b/src/main/java/frc/robot/subsystems/drive/module/ModuleIO.java index 17c080db..8d5aebd4 100644 --- a/src/main/java/frc/robot/subsystems/drive/module/ModuleIO.java +++ b/src/main/java/frc/robot/subsystems/drive/module/ModuleIO.java @@ -126,10 +126,10 @@ public void setOdometryTurnPositions(Rotation2d[] odometryTurnPositions) { default void updateInputs(ModuleIOInputs inputs) {} /** Run the drive motor at the specified voltage. */ - default void setDriveVoltage(double volts) {} + default void setDriveVelocityMPS(double mps) {} /** Run the turn motor at the specified voltage. */ - default void setTurnVoltage(double volts) {} + default void setTurnPositionDegs(double degrees) {} /** Enable or disable brake mode on the drive motor. */ default void setDriveBrakeMode(boolean enable) {} diff --git a/src/main/java/frc/robot/subsystems/drive/module/ModuleIOSim.java b/src/main/java/frc/robot/subsystems/drive/module/ModuleIOSim.java index 3fafb6e2..b3a15eb7 100644 --- a/src/main/java/frc/robot/subsystems/drive/module/ModuleIOSim.java +++ b/src/main/java/frc/robot/subsystems/drive/module/ModuleIOSim.java @@ -13,7 +13,10 @@ package frc.robot.subsystems.drive.module; +import com.gos.lib.properties.pid.PidProperty; +import com.gos.lib.properties.pid.WpiPidPropertyBuilder; import edu.wpi.first.math.MathUtil; +import edu.wpi.first.math.controller.PIDController; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.system.plant.DCMotor; import edu.wpi.first.wpilibj.simulation.DCMotorSim; @@ -28,11 +31,16 @@ public class ModuleIOSim implements ModuleIO { private static final double LOOP_PERIOD_SECS = 0.02; - private final DCMotorSim m_driveSim = new DCMotorSim(DCMotor.getNEO(1), 6.75, 0.025); - private final DCMotorSim m_turnSim = new DCMotorSim(DCMotor.getNEO(1), 150.0 / 7.0, 0.004); + private final DCMotorSim m_driveSim; + private final DCMotorSim m_turnSim; private final ModuleConstants m_moduleConstants; // use this mainly for module id + private final PIDController m_turnPid = new PIDController(0.0, 0.0, 0.0); + private final PIDController m_drivePid = new PIDController(0.0, 0.0, 0.0); + + private final PidProperty m_turnProperty; + private final PidProperty m_driveProperty; private final Rotation2d turnAbsoluteInitPosition = new Rotation2d(Math.random() * 2.0 * Math.PI); private double driveAppliedVolts = 0.0; @@ -40,17 +48,42 @@ public class ModuleIOSim implements ModuleIO { public ModuleIOSim(ModuleConstants moduleConstants) { m_moduleConstants = moduleConstants; + // create sims for motors + m_driveSim = new DCMotorSim(DCMotor.getFalcon500(1), m_moduleConstants.DRIVE_GEAR_RATIO(), 0.025); + m_turnSim = new DCMotorSim(DCMotor.getFalcon500(1), m_moduleConstants.TURNING_GEAR_RATIO(), 0.004); + + // setup default PID values for "onboard" controllers + m_turnProperty = new WpiPidPropertyBuilder("Sim Turn PID", false, m_turnPid) + .addP(m_moduleConstants.TURN_KP()) + .addI(m_moduleConstants.TURN_KI()) + .addD(m_moduleConstants.TURN_KD()) + .build(); + + m_driveProperty = new WpiPidPropertyBuilder("Sim Drive PID", false, m_drivePid) + .addP(m_moduleConstants.DRIVE_KP()) + .addI(m_moduleConstants.DRIVE_KI()) + .addD(m_moduleConstants.DRIVE_KD()) + .build(); + + // force update the values + m_turnProperty.updateIfChanged(true); + m_driveProperty.updateIfChanged(true); } @Override public void updateInputs(ModuleIOInputs inputs) { + // update the simulation m_driveSim.update(LOOP_PERIOD_SECS); m_turnSim.update(LOOP_PERIOD_SECS); - inputs.setDrivePositionRad(m_driveSim.getAngularPositionRad()); - inputs.setDriveVelocityRadPerSec(m_driveSim.getAngularVelocityRadPerSec()); - inputs.setDriveAppliedVolts(driveAppliedVolts); - inputs.setDriveCurrentAmps(new double[] {Math.abs(m_driveSim.getCurrentDrawAmps())}); + // update pid controllers + m_turnProperty.updateIfChanged(); + m_driveProperty.updateIfChanged(); + + inputs.drivePositionRad = m_driveSim.getAngularPositionRad(); + inputs.driveVelocityRadPerSec = m_driveSim.getAngularVelocityRadPerSec(); + inputs.driveAppliedVolts = driveAppliedVolts; + inputs.driveCurrentAmps = new double[] {Math.abs(m_driveSim.getCurrentDrawAmps())}; inputs.setTurnAbsolutePosition(new Rotation2d(m_turnSim.getAngularPositionRad()).plus(turnAbsoluteInitPosition)); inputs.setTurnPosition(new Rotation2d(m_turnSim.getAngularPositionRad())); @@ -63,13 +96,17 @@ public void updateInputs(ModuleIOInputs inputs) { } @Override - public void setDriveVoltage(double volts) { + public void setDriveVelocityMPS(double mps) { + double rps = (mps / m_moduleConstants.WHEEL_CURCUMFERENCE_METERS()) * m_moduleConstants.DRIVE_GEAR_RATIO(); + double volts = m_drivePid.calculate(m_driveSim.getAngularVelocityRPM() / 60, rps); driveAppliedVolts = MathUtil.clamp(volts, -12.0, 12.0); m_driveSim.setInputVoltage(driveAppliedVolts); } @Override - public void setTurnVoltage(double volts) { + public void setTurnPositionDegs(double degrees) { + double rots = degrees / 360; + double volts = m_turnPid.calculate(m_turnSim.getAngularPositionRotations(), rots); turnAppliedVolts = MathUtil.clamp(volts, -12.0, 12.0); m_turnSim.setInputVoltage(turnAppliedVolts); } diff --git a/src/main/java/frc/robot/subsystems/drive/module/ModuleIOSparkMax.java b/src/main/java/frc/robot/subsystems/drive/module/ModuleIOSparkMax.java index 50e8484e..e69de29b 100644 --- a/src/main/java/frc/robot/subsystems/drive/module/ModuleIOSparkMax.java +++ b/src/main/java/frc/robot/subsystems/drive/module/ModuleIOSparkMax.java @@ -1,171 +0,0 @@ -// Copyright 2021-2024 FRC 6328 -// http://github.com/Mechanical-Advantage -// -// This program is free software; you can redistribute it and/or -// modify it under the terms of the GNU General Public License -// version 3 as published by the Free Software Foundation or -// available in the root directory of this project. -// -// This program is distributed in the hope that it will be useful, -// but WITHOUT ANY WARRANTY; without even the implied warranty of -// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the -// GNU General Public License for more details. - -package frc.robot.subsystems.drive.module; - -import com.revrobotics.CANSparkBase.IdleMode; -import com.revrobotics.CANSparkLowLevel.MotorType; -import com.revrobotics.CANSparkLowLevel.PeriodicFrame; -import com.revrobotics.CANSparkMax; -import com.revrobotics.RelativeEncoder; -import edu.wpi.first.math.geometry.Rotation2d; -import edu.wpi.first.math.util.Units; -import edu.wpi.first.wpilibj.AnalogInput; -import edu.wpi.first.wpilibj.RobotController; -import java.util.Queue; - -/** - * Module IO implementation for SparkMax drive motor controller, SparkMax turn motor controller (NEO - * or NEO 550), and analog absolute encoder connected to the RIO - * - *
NOTE: This implementation should be used as a starting point and adapted to different hardware - * configurations (e.g. If using a CANcoder, copy from "ModuleIOTalonFX") - * - *
To calibrate the absolute encoder offsets, point the modules straight (such that forward
- * motion on the drive motor will propel the robot forward) and copy the reported values from the
- * absolute encoders using AdvantageScope. These values are logged under
- * "/Drive/ModuleX/TurnAbsolutePositionRad"
- */
-public class ModuleIOSparkMax implements ModuleIO {
- // Gear ratios for SDS MK4i L2, adjust as necessary
- private static final double DRIVE_GEAR_RATIO = (50.0 / 14.0) * (17.0 / 27.0) * (45.0 / 15.0);
- private static final double TURN_GEAR_RATIO = 150.0 / 7.0;
-
- private final CANSparkMax driveSparkMax;
- private final CANSparkMax turnSparkMax;
-
- private final RelativeEncoder driveEncoder;
- private final RelativeEncoder turnRelativeEncoder;
- private final AnalogInput turnAbsoluteEncoder;
- private final Queue