Skip to content

Commit

Permalink
Basic intake done
Browse files Browse the repository at this point in the history
  • Loading branch information
keckothedragon committed May 9, 2024
1 parent d0f4632 commit 831dc75
Show file tree
Hide file tree
Showing 36 changed files with 543 additions and 37 deletions.
Binary file added advantagekit/logs/Log_24-05-09_14-31-16.wpilog
Binary file not shown.
Binary file added advantagekit/logs/Log_24-05-09_14-31-37.wpilog
Binary file not shown.
Binary file added advantagekit/logs/Log_24-05-09_14-32-06.wpilog
Binary file not shown.
Binary file added advantagekit/logs/Log_24-05-09_14-35-32.wpilog
Binary file not shown.
Binary file added advantagekit/logs/Log_24-05-09_14-36-50.wpilog
Binary file not shown.
Binary file added advantagekit/logs/Log_24-05-09_14-37-40.wpilog
Binary file not shown.
Binary file added advantagekit/logs/Log_24-05-09_14-38-44.wpilog
Binary file not shown.
Binary file added advantagekit/logs/Log_24-05-09_14-39-29.wpilog
Binary file not shown.
Binary file added advantagekit/logs/Log_24-05-09_14-40-56.wpilog
Binary file not shown.
Binary file added advantagekit/logs/Log_70bac4a28b84b662.wpilog
Binary file not shown.
Binary file added advantagekit/logs/Log_a939221437849ad8.wpilog
Binary file not shown.
Binary file modified ctre_sim/Pigeon 2 - 020 - 0 - ext.dat
Binary file not shown.
Binary file added logs/FRC_20240509_183119.wpilog
Binary file not shown.
Binary file added logs/FRC_20240509_183208.wpilog
Binary file not shown.
Binary file added logs/FRC_20240509_183538.wpilog
Binary file not shown.
Binary file added logs/FRC_20240509_183658.wpilog
Binary file not shown.
Binary file added logs/FRC_20240509_183742.wpilog
Binary file not shown.
Binary file added logs/FRC_20240509_183846.wpilog
Binary file not shown.
Binary file added logs/FRC_20240509_183933.wpilog
Binary file not shown.
Binary file added logs/FRC_20240509_184100.wpilog
Binary file not shown.
Binary file removed logs/FRC_TBD_68992208bb6a5cd3.wpilog
Binary file not shown.
122 changes: 122 additions & 0 deletions src/main/java/frc/lib/utils/LoggedTunableNumber.java
Original file line number Diff line number Diff line change
@@ -0,0 +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;

/**
* 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<>();

/**
* Create a new LoggedTunableNumber
*
* @param dashboardKey Key on dashboard
*/
public LoggedTunableNumber(String dashboardKey, String tableKey) {
this.key = tableKey + "/" + dashboardKey;
// this.key = tableKey + "/" + dashboardKey;
}

/**
* 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);
}

public LoggedTunableNumber(String dashboardKey, double defaultValue, String tableKey) {
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);
}
}
}

/**
* 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;
}
}

public void set(double val) {
dashboardNumber.set(val);
}

/**
* 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;
}

return false;
}

/**
* 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);
}
}
55 changes: 44 additions & 11 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.trajectory.TrapezoidProfile.Constraints;
import edu.wpi.first.math.util.Units;
import frc.lib.utils.TunableNumber;
import frc.lib.utils.LoggedTunableNumber;

/**
* The Constants class provides a convenient place for teams to hold robot-wide numerical or boolean
Expand All @@ -39,11 +39,14 @@ public static final class ShooterConstants {
public static final Rotation2d kMinAngle = Rotation2d.fromDegrees(30);
public static final Rotation2d kHomeAngle = Rotation2d.fromDegrees(45);

public static final TunableNumber kPivotP = new TunableNumber("Shooter Pivot P", 1.0);
public static final TunableNumber kPivotI = new TunableNumber("Shooter Pivot I", 0.0);
public static final TunableNumber kPivotD = new TunableNumber("Shooter Pivot D", 0.0);
public static final double kPivotVelocity = 5.0;
public static final double kPivotAcceleration = 10.0;
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 = 10.0;
public static final double kPivotAcceleration = 15.0;
public static final ProfiledPIDController kPivotController =
new ProfiledPIDController(
kPivotP.get(),
Expand All @@ -54,11 +57,14 @@ public static final class ShooterConstants {
// Shooter flywheel
public static final double kFlywheelDiameter = Units.inchesToMeters(4.0);

public static final TunableNumber kFlywheelP = new TunableNumber("Shooter Flywheel P", 5.0);
public static final TunableNumber kFlywheelI = new TunableNumber("Shooter Flywheel I", 0.0);
public static final TunableNumber kFlywheelD = new TunableNumber("Shooter Flywheel D", 0.0);
public static final double kFlywheelVelocity = 5.0;
public static final double kFlywheelAcceleration = 10.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 = 10.0;
public static final double kFlywheelAcceleration = 15.0;
public static final ProfiledPIDController kFlywheelController =
new ProfiledPIDController(
kFlywheelP.get(),
Expand All @@ -67,12 +73,39 @@ public static final class ShooterConstants {
new Constraints(kFlywheelVelocity, kFlywheelAcceleration));
}

public static final class IntakeConstants {
public static final double kPivotGearRatio = 36.0 / 16;

// TODO: untuned values, fix later
public static final Rotation2d kMaxAngle = Rotation2d.fromDegrees(90);
public static final Rotation2d kMinAngle = Rotation2d.fromDegrees(0);
public static final Rotation2d kHomeAngle = Rotation2d.fromDegrees(85);

public static final LoggedTunableNumber kPivotP =
new LoggedTunableNumber("Intake Pivot P", 1.0);
public static final LoggedTunableNumber kPivotI =
new LoggedTunableNumber("Intake Pivot I", 0.0);
public static final LoggedTunableNumber kPivotD =
new LoggedTunableNumber("Intake Pivot D", 0.0);
public static final double kPivotVelocity = 10.0;
public static final double kPivotAcceleration = 15.0;
public static final ProfiledPIDController kPivotController =
new ProfiledPIDController(
kPivotP.get(),
kPivotI.get(),
kPivotD.get(),
new Constraints(kPivotVelocity, kPivotAcceleration));
}

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 kFlywheelLeft = 0;
public static final int kFlywheelRight = 0;

public static final int kIntakePivot = 0;
public static final int kIntakeRoller = 0;
}
}
34 changes: 33 additions & 1 deletion src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.wpilibj.RobotBase;
import edu.wpi.first.wpilibj2.command.Commands;
import frc.robot.Constants.IntakeConstants;
import frc.robot.Constants.Ports;
import frc.robot.Constants.ShooterConstants;
import frc.robot.commands.DriveCommands;
Expand All @@ -25,6 +26,11 @@
import frc.robot.subsystems.drive.GyroIOPigeon2;
import frc.robot.subsystems.drive.ModuleIOSim;
import frc.robot.subsystems.drive.ModuleIOTalonFX;
import frc.robot.subsystems.intake.Intake;
import frc.robot.subsystems.intake.pivot.IntakePivotIONeo;
import frc.robot.subsystems.intake.pivot.IntakePivotIOSim;
import frc.robot.subsystems.intake.roller.RollerIOKraken;
import frc.robot.subsystems.intake.roller.RollerIOSim;
import frc.robot.subsystems.shooter.Shooter;
import frc.robot.subsystems.shooter.flywheel.FlywheelIOKraken;
import frc.robot.subsystems.shooter.flywheel.FlywheelIOSim;
Expand All @@ -43,6 +49,7 @@ public class RobotContainer {
// Subsystems
private Drive m_drive;
private Shooter m_shooter;
private Intake m_intake;

// Controllers
private DriverControls m_driverControls;
Expand Down Expand Up @@ -73,6 +80,12 @@ private void configureSubsystems() {
new FlywheelIOKraken(Ports.kFlywheelLeft, Ports.kFlywheelRight),
ShooterConstants.kPivotController,
ShooterConstants.kFlywheelController);

m_intake =
new Intake(
new RollerIOKraken(Ports.kIntakeRoller),
new IntakePivotIONeo(Ports.kIntakePivot),
IntakeConstants.kPivotController);
} else {
m_drive =
new Drive(
Expand All @@ -87,11 +100,15 @@ private void configureSubsystems() {
new FlywheelIOSim(),
ShooterConstants.kPivotController,
ShooterConstants.kFlywheelController);

m_intake =
new Intake(new RollerIOSim(), new IntakePivotIOSim(), IntakeConstants.kPivotController);
}

m_shooter.setPivotAngle(ShooterConstants.kHomeAngle);
m_intake.setPivotAngle(IntakeConstants.kHomeAngle);

m_robotState = RobotState.startInstance(m_drive, m_shooter);
m_robotState = RobotState.startInstance(m_drive, m_shooter, m_intake);
}

private void configureControllers() {
Expand Down Expand Up @@ -120,6 +137,21 @@ private void configureButtonBindings() {
m_shooter.setFlywheelVelocity(0.0, 0.0);
m_shooter.setPivotAngle(ShooterConstants.kHomeAngle);
}));

m_driverControls
.testIntake()
.onTrue(
Commands.runOnce(
() -> {
m_intake.setRollerVoltage(12);
m_intake.setPivotAngle(Rotation2d.fromDegrees(15));
}))
.onFalse(
Commands.runOnce(
() -> {
m_intake.setRollerVoltage(0);
m_intake.setPivotAngle(IntakeConstants.kHomeAngle);
}));
}

public void updateRobotState() {
Expand Down
29 changes: 22 additions & 7 deletions src/main/java/frc/robot/RobotState.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
import edu.wpi.first.wpilibj.util.Color;
import edu.wpi.first.wpilibj.util.Color8Bit;
import frc.robot.subsystems.drive.Drive;
import frc.robot.subsystems.intake.Intake;
import frc.robot.subsystems.shooter.Shooter;

public class RobotState {
Expand All @@ -15,35 +16,48 @@ public class RobotState {
// subsystems
private Drive m_drive;
private Shooter m_shooter;
private Intake m_intake;

// mechanism
private final boolean kMechanismEnabled = true;
MechanismLigament2d m_shooterPivotMech;
MechanismLigament2d m_intakePivotMech;

private RobotState(Drive drive, Shooter shooter) {
private RobotState(Drive drive, Shooter shooter, Intake intake) {
// subsystems
m_drive = drive;
m_shooter = shooter;
m_intake = intake;

// mechanism set up
Mechanism2d m_mechanism = new Mechanism2d(3, 3);
MechanismRoot2d m_root = m_mechanism.getRoot("shooter", 3, 1);
Mechanism2d mechanism = new Mechanism2d(3, 3);
MechanismRoot2d shooterRoot = mechanism.getRoot("shooter", 2, 1);
m_shooterPivotMech =
m_root.append(
shooterRoot.append(
new MechanismLigament2d(
"pivot",
1,
m_shooter.getPivotAngle().getDegrees(),
6,
new Color8Bit(Color.kPurple)));

MechanismRoot2d intakeRoot = mechanism.getRoot("intake", 1, 1);
m_intakePivotMech =
intakeRoot.append(
new MechanismLigament2d(
"pivot",
1,
180 - m_intake.getPivotAngle().getDegrees(),
6,
new Color8Bit(Color.kBlue)));

// post to dashboard
SmartDashboard.putData("Mech2d", m_mechanism);
SmartDashboard.putData("Mech2d", mechanism);
}

public static RobotState startInstance(Drive drive, Shooter shooter) {
public static RobotState startInstance(Drive drive, Shooter shooter, Intake intake) {
if (instance == null) {
instance = new RobotState(drive, shooter);
instance = new RobotState(drive, shooter, intake);
} else {
throw new IllegalStateException("RobotState instance already started");
}
Expand All @@ -59,6 +73,7 @@ public static RobotState getInstance() {

public void updateMechanism() {
m_shooterPivotMech.setAngle(m_shooter.getPivotAngle().getDegrees());
m_intakePivotMech.setAngle(180 - m_intake.getPivotAngle().getDegrees());
}

public void updateRobotState() {
Expand Down
2 changes: 2 additions & 0 deletions src/main/java/frc/robot/oi/DriverControls.java
Original file line number Diff line number Diff line change
Expand Up @@ -10,4 +10,6 @@ public interface DriverControls {
public double getDriveRotation();

public Trigger testShooter();

public Trigger testIntake();
}
5 changes: 5 additions & 0 deletions src/main/java/frc/robot/oi/DriverControlsPS5.java
Original file line number Diff line number Diff line change
Expand Up @@ -29,4 +29,9 @@ public double getDriveRotation() {
public Trigger testShooter() {
return m_controller.L2();
}

@Override
public Trigger testIntake() {
return m_controller.circle();
}
}
7 changes: 6 additions & 1 deletion src/main/java/frc/robot/oi/DriverControlsXbox.java
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,11 @@ public double getDriveRotation() {

@Override
public Trigger testShooter() {
return m_controller.button(7);
return m_controller.button(1);
}

@Override
public Trigger testIntake() {
return m_controller.button(3);
}
}
Loading

0 comments on commit 831dc75

Please sign in to comment.