Skip to content

Commit

Permalink
Added port numbers and slightly tuned pid
Browse files Browse the repository at this point in the history
  • Loading branch information
keckothedragon committed May 12, 2024
1 parent 97b33fc commit ea8cce0
Show file tree
Hide file tree
Showing 12 changed files with 348 additions and 293 deletions.
191 changes: 96 additions & 95 deletions src/main/java/frc/lib/utils/LoggedTunableNumber.java
Original file line number Diff line number Diff line change
@@ -1,121 +1,122 @@
package frc.lib.utils;

import frc.robot.Constants;
// FROM 6328 Mechanical Advantage
import java.util.Arrays;
import java.util.HashMap;
import java.util.Map;
import java.util.function.Consumer;
import org.littletonrobotics.junction.networktables.LoggedDashboardNumber;
import frc.robot.Constants;
// FROM 6328 Mechanical Advantage

/**
* Class for a tunable number. Gets value from dashboard in tuning mode, returns default if not or
* value not in dashboard.
*/
public class LoggedTunableNumber {
private static final String tableKey = "TunableNumbers";

private final String key;
private boolean hasDefault = false;
private double defaultValue;
private LoggedDashboardNumber dashboardNumber;
private Map<Integer, Double> lastHasChangedValues = new HashMap<>();
private static final String tableKey = "TunableNumbers";

/**
* Create a new LoggedTunableNumber
*
* @param dashboardKey Key on dashboard
*/
public LoggedTunableNumber(String dashboardKey, String tableKey) {
this.key = tableKey + "/" + dashboardKey;
// this.key = tableKey + "/" + dashboardKey;
}
private final String key;
private boolean hasDefault = false;
private double defaultValue;
private LoggedDashboardNumber dashboardNumber;
private Map<Integer, Double> lastHasChangedValues = new HashMap<>();

/**
* Create a new LoggedTunableNumber with the default value
*
* @param dashboardKey Key on dashboard
* @param defaultValue Default value
*/
public LoggedTunableNumber(String dashboardKey, double defaultValue) {
this(dashboardKey, tableKey);
initDefault(defaultValue);
}
/**
* Create a new LoggedTunableNumber
*
* @param dashboardKey Key on dashboard
*/
public LoggedTunableNumber(String dashboardKey, String tableKey) {
this.key = tableKey + "/" + dashboardKey;
// this.key = tableKey + "/" + dashboardKey;
}

public LoggedTunableNumber(String dashboardKey, double defaultValue, String tableKey) {
this(dashboardKey, tableKey);
initDefault(defaultValue);
}
/**
* Create a new LoggedTunableNumber with the default value
*
* @param dashboardKey Key on dashboard
* @param defaultValue Default value
*/
public LoggedTunableNumber(String dashboardKey, double defaultValue) {
this(dashboardKey, tableKey);
initDefault(defaultValue);
}

/**
* Set the default value of the number. The default value can only be set once.
*
* @param defaultValue The default value
*/
public void initDefault(double defaultValue) {
if (!hasDefault) {
hasDefault = true;
this.defaultValue = defaultValue;
if (Constants.tuningMode) {
dashboardNumber = new LoggedDashboardNumber(key, defaultValue);
}
}
}
public LoggedTunableNumber(String dashboardKey, double defaultValue, String tableKey) {
this(dashboardKey, tableKey);
initDefault(defaultValue);
}

/**
* Get the current value, from dashboard if available and in tuning mode.
*
* @return The current value
*/
public double get() {
if (!hasDefault) {
return 0.0;
} else {
return Constants.tuningMode ? dashboardNumber.get() : defaultValue;
}
/**
* Set the default value of the number. The default value can only be set once.
*
* @param defaultValue The default value
*/
public void initDefault(double defaultValue) {
if (!hasDefault) {
hasDefault = true;
this.defaultValue = defaultValue;
if (Constants.tuningMode) {
dashboardNumber = new LoggedDashboardNumber(key, defaultValue);
}
}
}

public void set(double val){
dashboardNumber.set(val);
/**
* Get the current value, from dashboard if available and in tuning mode.
*
* @return The current value
*/
public double get() {
if (!hasDefault) {
return 0.0;
} else {
return Constants.tuningMode ? dashboardNumber.get() : defaultValue;
}
}

/**
* Checks whether the number has changed since our last check
*
* @param id Unique identifier for the caller to avoid conflicts when shared between multiple
* objects. Recommended approach is to pass the result of "hashCode()"
* @return True if the number has changed since the last time this method was called, false
* otherwise.
*/
public boolean hasChanged(int id) {
if (!Constants.tuningMode) return false;
double currentValue = get();
Double lastValue = lastHasChangedValues.get(id);
if (lastValue == null || currentValue != lastValue) {
lastHasChangedValues.put(id, currentValue);
return true;
}
public void set(double val) {
dashboardNumber.set(val);
}

return false;
/**
* Checks whether the number has changed since our last check
*
* @param id Unique identifier for the caller to avoid conflicts when shared between multiple
* objects. Recommended approach is to pass the result of "hashCode()"
* @return True if the number has changed since the last time this method was called, false
* otherwise.
*/
public boolean hasChanged(int id) {
if (!Constants.tuningMode) return false;
double currentValue = get();
Double lastValue = lastHasChangedValues.get(id);
if (lastValue == null || currentValue != lastValue) {
lastHasChangedValues.put(id, currentValue);
return true;
}

/**
* Runs action if any of the tunableNumbers have changed
*
* @param id Unique identifier for the caller to avoid conflicts when shared between multiple *
* objects. Recommended approach is to pass the result of "hashCode()"
* @param action Callback to run when any of the tunable numbers have changed. Access tunable
* numbers in order inputted in method
* @param tunableNumbers All tunable numbers to check
*/
public static void ifChanged(
int id, Consumer<double[]> action, LoggedTunableNumber... tunableNumbers) {
if (Arrays.stream(tunableNumbers).anyMatch(tunableNumber -> tunableNumber.hasChanged(id))) {
action.accept(Arrays.stream(tunableNumbers).mapToDouble(LoggedTunableNumber::get).toArray());
}
}
return false;
}

/** Runs action if any of the tunableNumbers have changed */
public static void ifChanged(int id, Runnable action, LoggedTunableNumber... tunableNumbers) {
ifChanged(id, values -> action.run(), tunableNumbers);
/**
* Runs action if any of the tunableNumbers have changed
*
* @param id Unique identifier for the caller to avoid conflicts when shared between multiple *
* objects. Recommended approach is to pass the result of "hashCode()"
* @param action Callback to run when any of the tunable numbers have changed. Access tunable
* numbers in order inputted in method
* @param tunableNumbers All tunable numbers to check
*/
public static void ifChanged(
int id, Consumer<double[]> action, LoggedTunableNumber... tunableNumbers) {
if (Arrays.stream(tunableNumbers).anyMatch(tunableNumber -> tunableNumber.hasChanged(id))) {
action.accept(Arrays.stream(tunableNumbers).mapToDouble(LoggedTunableNumber::get).toArray());
}
}
}

/** Runs action if any of the tunableNumbers have changed */
public static void ifChanged(int id, Runnable action, LoggedTunableNumber... tunableNumbers) {
ifChanged(id, values -> action.run(), tunableNumbers);
}
}
80 changes: 56 additions & 24 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -35,13 +35,18 @@ public static final class ShooterConstants {
// Shooter pivot
public static final double kPivotGearRatio = 46.722;
// TODO: untuned values, fix later
public static final Rotation2d kMaxAngle = Rotation2d.fromDegrees(70);
public static final Rotation2d kMinAngle = Rotation2d.fromDegrees(30);
public static final Rotation2d kHomeAngle = Rotation2d.fromDegrees(45);
public static final Rotation2d kMaxAngle = Rotation2d.fromDegrees(55);
public static final Rotation2d kMinAngle = Rotation2d.fromDegrees(15);
public static final Rotation2d kHomeAngle = Rotation2d.fromDegrees(33);

public static final LoggedTunableNumber kPivotP = new LoggedTunableNumber("Shooter Pivot P", 1.0);
public static final LoggedTunableNumber kPivotI = new LoggedTunableNumber("Shooter Pivot I", 0.0);
public static final LoggedTunableNumber kPivotD = new LoggedTunableNumber("Shooter Pivot D", 0.0);
public static final Rotation2d kPivotOffset = Rotation2d.fromDegrees(170);

public static final LoggedTunableNumber kPivotP =
new LoggedTunableNumber("Shooter Pivot P", 1.0);
public static final LoggedTunableNumber kPivotI =
new LoggedTunableNumber("Shooter Pivot I", 0.0);
public static final LoggedTunableNumber kPivotD =
new LoggedTunableNumber("Shooter Pivot D", 0.0);
public static final double kPivotVelocity = 5.0;
public static final double kPivotAcceleration = 10.0;
public static final ProfiledPIDController kPivotController =
Expand All @@ -54,29 +59,56 @@ public static final class ShooterConstants {
// Shooter flywheel
public static final double kFlywheelDiameter = Units.inchesToMeters(4.0);

public static final LoggedTunableNumber kFlywheelP = new LoggedTunableNumber("Shooter Flywheel P", 5.0);
public static final LoggedTunableNumber kFlywheelI = new LoggedTunableNumber("Shooter Flywheel I", 0.0);
public static final LoggedTunableNumber kFlywheelD = new LoggedTunableNumber("Shooter Flywheel D", 0.0);
public static final double kFlywheelVelocity = 5.0;
public static final double kFlywheelAcceleration = 10.0;
public static final ProfiledPIDController kFlywheelController =
public static final LoggedTunableNumber kLeftFlywheelP =
new LoggedTunableNumber("Shooter Flywheel P", 0.7);
public static final LoggedTunableNumber kLeftFlywheelI =
new LoggedTunableNumber("Shooter Flywheel I", 0.0);
public static final LoggedTunableNumber kLeftFlywheelD =
new LoggedTunableNumber("Shooter Flywheel D", 0.0);
public static final double kLeftFlywheelVelocity = 10.0;
public static final double kLeftFlywheelAcceleration = 15.0;
public static final ProfiledPIDController kLeftFlywheelController =
new ProfiledPIDController(
kLeftFlywheelP.get(),
kLeftFlywheelI.get(),
kLeftFlywheelD.get(),
new Constraints(kLeftFlywheelVelocity, kLeftFlywheelAcceleration));

public static final LoggedTunableNumber kRightFlywheelP =
new LoggedTunableNumber("Shooter Flywheel P", 0.7);
public static final LoggedTunableNumber kRightFlywheelI =
new LoggedTunableNumber("Shooter Flywheel I", 0.0);
public static final LoggedTunableNumber kRightFlywheelD =
new LoggedTunableNumber("Shooter Flywheel D", 0.0);
public static final double kRightFlywheelVelocity = 10.0;
public static final double kRightFlywheelAcceleration = 15.0;
public static final ProfiledPIDController kRightFlywheelController =
new ProfiledPIDController(
kFlywheelP.get(),
kFlywheelI.get(),
kFlywheelD.get(),
new Constraints(kFlywheelVelocity, kFlywheelAcceleration));
kRightFlywheelP.get(),
kRightFlywheelI.get(),
kRightFlywheelD.get(),
new Constraints(kRightFlywheelVelocity, kRightFlywheelAcceleration));
}

public static final class Ports {
public static final int kShooterPivotLeader = 0;
public static final int kShooterPivotFollower = 0;
public static final int kShooterPivotEncoder = 0;
public static final int kShooterPivotLeader = 39;
public static final int kShooterPivotFollower = 40;
public static final int kShooterPivotEncoder = 9;

public static final int kFlywheelLeft = 35;
public static final int kFlywheelRight = 36;

public static final int kKicker = 31;
public static final int kFeeder = 30;
public static final int kIndexerBeamBreakOne = 2;
public static final int kIndexerBeamBreakTwo = 3;

public static final int kIntakeRoller = 43;
public static final int kIntakePivot = 0;

public static final int kFlywheelLeft = 0;
public static final int kFlywheelRight = 0;
public static final int kClimbUp = 26;
public static final int kClimbDown = 25;

public static final int kIndexerMotor = 0;
public static final int kIndexerBeamBreakOne = 0;
public static final int kIndexerBeamBreakTwo = 0;
public static final int kAmp = 54;
}
}
30 changes: 15 additions & 15 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
import frc.robot.Constants.ShooterConstants;
import frc.robot.commands.DriveCommands;
import frc.robot.oi.DriverControls;
import frc.robot.oi.DriverControlsXbox;
import frc.robot.oi.DriverControlsPS5;
import frc.robot.subsystems.drive.Drive;
import frc.robot.subsystems.drive.GyroIOPigeon2;
import frc.robot.subsystems.drive.ModuleIOSim;
Expand Down Expand Up @@ -75,12 +75,12 @@ private void configureSubsystems() {
Ports.kShooterPivotEncoder),
new FlywheelIOKraken(Ports.kFlywheelLeft, Ports.kFlywheelRight),
ShooterConstants.kPivotController,
ShooterConstants.kFlywheelController);
ShooterConstants.kLeftFlywheelController,
ShooterConstants.kRightFlywheelController);
m_indexer =
new Indexer(
new IndexerIOFalcon(Ports.kIndexerMotor,
Ports.kIndexerBeamBreakOne,
Ports.kIndexerBeamBreakTwo));
new IndexerIOFalcon(
Ports.kKicker, Ports.kIndexerBeamBreakOne, Ports.kIndexerBeamBreakTwo));
} else {
m_drive =
new Drive(
Expand All @@ -94,7 +94,8 @@ private void configureSubsystems() {
new ShooterPivotIOSim(),
new FlywheelIOSim(),
ShooterConstants.kPivotController,
ShooterConstants.kFlywheelController);
ShooterConstants.kLeftFlywheelController,
ShooterConstants.kRightFlywheelController);
m_indexer = new Indexer(new IndexerIOSim());
}

Expand All @@ -104,7 +105,7 @@ private void configureSubsystems() {
}

private void configureControllers() {
m_driverControls = new DriverControlsXbox(1);
m_driverControls = new DriverControlsPS5(1);
}

private void configureButtonBindings() {
Expand All @@ -120,21 +121,20 @@ private void configureButtonBindings() {
.onTrue(
Commands.runOnce(
() -> {
m_shooter.setFlywheelVelocity(2, 4);
m_shooter.setPivotAngle(Rotation2d.fromDegrees(60));
m_shooter.setFlywheelVelocity(10, 13);
m_shooter.setPivotAngle(Rotation2d.fromDegrees(45));
}))
.onFalse(
Commands.runOnce(
() -> {
m_shooter.setFlywheelVelocity(0.0, 0.0);
m_shooter.setPivotAngle(ShooterConstants.kHomeAngle);
}));

m_driverControls.testIndexer().onTrue(
m_indexer.runIndexer(6.0)
).onFalse(
m_indexer.runIndexer(0.0)
);

m_driverControls
.testIndexer()
.onTrue(m_indexer.runIndexer(6.0))
.onFalse(m_indexer.runIndexer(0.0));
}

public void updateRobotState() {
Expand Down
Loading

0 comments on commit ea8cce0

Please sign in to comment.