Skip to content

Commit

Permalink
Merge branch 'Intaking-stuff-sim' of https://github.com/FRC-7525/2024…
Browse files Browse the repository at this point in the history
…-Progathon into Intaking-stuff-sim
  • Loading branch information
GreenTomato5 committed Jan 2, 2025
2 parents a4ca529 + 377674b commit ee2d1d1
Show file tree
Hide file tree
Showing 4 changed files with 18 additions and 16 deletions.
16 changes: 8 additions & 8 deletions src/main/java/frc/robot/subsystems/Indexer/Indexer.java
Original file line number Diff line number Diff line change
@@ -1,12 +1,11 @@
package frc.robot.subsystems.Indexer;

import static edu.wpi.first.units.Units.Seconds;

import frc.robot.GlobalConstants;
import frc.robot.GlobalConstants.RobotMode;
import frc.robot.pioneersLib.subsystem.Subsystem;
import frc.robot.subsystems.Intake.Intake;

import static edu.wpi.first.units.Units.Seconds;

import org.littletonrobotics.junction.Logger;

public class Indexer extends Subsystem<IndexerStates> {
Expand All @@ -17,15 +16,16 @@ public class Indexer extends Subsystem<IndexerStates> {

private Indexer() {
super("Indexer", IndexerStates.OFF);

addTrigger(IndexerStates.AUTONOMOUS_ON, IndexerStates.AUTONOMOUS_OFF, () ->
{if (GlobalConstants.ROBOT_MODE == RobotMode.SIM) {
addTrigger(IndexerStates.AUTONOMOUS_ON, IndexerStates.AUTONOMOUS_OFF, () -> {
if (GlobalConstants.ROBOT_MODE == RobotMode.SIM) {
return getStateTime() > IndexerConstants.SIMULATED_INDEXING_TIME.in(Seconds);
} else {
return io.nextSensorTriggered();
}}
}
});
addTrigger(IndexerStates.AUTONOMOUS_OFF, IndexerStates.AUTONOMOUS_ON, () ->
Intake.getInstance().hasGamepiece()
);
addTrigger(IndexerStates.AUTONOMOUS_OFF, IndexerStates.AUTONOMOUS_ON, () -> Intake.getInstance().hasGamepiece());

this.io = switch (GlobalConstants.ROBOT_MODE) {
case SIM -> new IndexerIOSim();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,11 +40,12 @@ public static final class Sim {
public static final MomentOfInertia WHEEL_MOTOR_MOI = KilogramSquareMeters.of(1); // random value
public static final double WHEEL_MOTOR_GEARING = 3;
public static final PIDConstants WHEEL_PID_CONSTANTS = new PIDConstants(0.0012, 0, 0);

public static final Time SIMULATED_INTAKING_TIME = Seconds.of(1);
}

public static final class Real {

public static final int WHEEL_MOTOR_CANID = 10;
public static final int PIVOT_MOTOR_CANID = 11;
public static final int BEAM_BREAK_DIO_PORT = 10;
Expand Down
13 changes: 7 additions & 6 deletions src/main/java/frc/robot/subsystems/Intake/IntakeIO.java
Original file line number Diff line number Diff line change
@@ -1,8 +1,7 @@
package frc.robot.subsystems.Intake;

import org.littletonrobotics.junction.AutoLog;

import com.fasterxml.jackson.databind.ser.std.StdKeySerializers.Default;
import org.littletonrobotics.junction.AutoLog;

public interface IntakeIO {
@AutoLog
Expand All @@ -17,11 +16,13 @@ public static class IntakeIOInputs {
public double wheelSpeedSetpoint;
}

public default void updateInputs(IntakeIOInputs input) {};
public default void updateInputs(IntakeIOInputs input) {}

public default void setPivotSetpoint(double pivotSetpoint) {};
public default void setPivotSetpoint(double pivotSetpoint) {}

public default void setWheelSpeed(double wheelSpeed) {};
public default void setWheelSpeed(double wheelSpeed) {}

public default boolean hasGamepiece() {return false;};
public default boolean hasGamepiece() {
return false;
}
}
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/subsystems/Manager/Manager.java
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ private Manager() {
() -> TEST_CONTROLLER.getYButtonPressed()
);
}

// from idle
addTrigger(ManagerStates.IDLE, ManagerStates.INTAKING, () ->
Controllers.DRIVER_CONTROLLER.getBButtonPressed()
Expand Down

0 comments on commit ee2d1d1

Please sign in to comment.