Skip to content

Commit

Permalink
WPI Testing
Browse files Browse the repository at this point in the history
Co-authored-by: suryatho <[email protected]>
  • Loading branch information
camearle20 and suryatho committed Feb 10, 2024
1 parent 1772db5 commit ecf86d0
Show file tree
Hide file tree
Showing 15 changed files with 88 additions and 105 deletions.
2 changes: 1 addition & 1 deletion src/main/java/org/littletonrobotics/frc2024/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,7 @@ public void robotInit() {
setUseTiming(false); // Run as fast as possible
String logPath = LogFileUtil.findReplayLog();
Logger.setReplaySource(new WPILOGReader(logPath));
Logger.addDataReceiver(new WPILOGWriter(LogFileUtil.addPathSuffix(logPath, "_sim")));
Logger.addDataReceiver(new WPILOGWriter(LogFileUtil.addPathSuffix(logPath, "_sim"), 0.01));
break;
}

Expand Down
18 changes: 12 additions & 6 deletions src/main/java/org/littletonrobotics/frc2024/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -106,7 +106,7 @@ public RobotContainer() {
AprilTagVisionConstants.instanceNames[1],
AprilTagVisionConstants.cameraIds[1]));
intake = new Intake(new IntakeIOKrakenFOC());
superstructure = new Superstructure(arm, flywheels, feeder);
superstructure = new Superstructure(arm, flywheels, feeder, intake);
}
case SIMBOT -> {
drive =
Expand All @@ -120,7 +120,7 @@ public RobotContainer() {
flywheels = new Flywheels(new FlywheelsIOSim());
intake = new Intake(new IntakeIOSim());
feeder = new Feeder(new FeederIOSim());
superstructure = new Superstructure(arm, flywheels, feeder);
superstructure = new Superstructure(arm, flywheels, feeder, intake);
}
case COMPBOT -> {
// No impl yet
Expand Down Expand Up @@ -164,7 +164,7 @@ public RobotContainer() {
}

if (superstructure == null) {
superstructure = new Superstructure(arm, flywheels, feeder);
superstructure = new Superstructure(arm, flywheels, feeder, intake);
}

autoChooser = new LoggedDashboardChooser<>("Auto Choices");
Expand Down Expand Up @@ -224,8 +224,6 @@ private void configureButtonBindings() {
drive.setTeleopDriveGoal(
-controller.getLeftY(), -controller.getLeftX(), -controller.getRightX())));

controller.rightBumper().onTrue(intake.intakeCommand()).onFalse(intake.stopCommand());

controller
.leftTrigger()
.onTrue(Commands.runOnce(drive::setAutoAimGoal))
Expand Down Expand Up @@ -263,7 +261,15 @@ private void configureButtonBindings() {
.leftBumper()
.onTrue(
Commands.runOnce(
() -> superstructure.setGoalState(Superstructure.SystemState.INTAKE)))
() -> superstructure.setGoalState(Superstructure.SystemState.STATION_INTAKE)))
.onFalse(
Commands.runOnce(() -> superstructure.setGoalState(Superstructure.SystemState.IDLE)));

controller
.a()
.onTrue(
Commands.runOnce(
() -> superstructure.setGoalState(Superstructure.SystemState.REVERSE_INTAKE)))
.onFalse(
Commands.runOnce(() -> superstructure.setGoalState(Superstructure.SystemState.IDLE)));
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,6 @@
import edu.wpi.first.wpilibj2.command.Commands;
import java.util.function.Supplier;
import org.littletonrobotics.frc2024.RobotState;
import org.littletonrobotics.frc2024.subsystems.superstructure.intake.Intake;

public class AutoCommands {

Expand All @@ -17,14 +16,6 @@ public static Command waitForRegion(Supplier<Region> region) {
return Commands.waitUntil(() -> inRegion(region));
}

public static Command intakeWhileInRegion(Intake intake, Supplier<Region> region) {
return Commands.sequence(
Commands.waitUntil(() -> inRegion(region)),
intake.intakeCommand(),
Commands.waitUntil(() -> !inRegion(region)),
intake.stopCommand());
}

public interface Region {
boolean contains(Translation2d point);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -78,10 +78,11 @@ public ModuleIOSparkMax(ModuleConfig config) {

driveMotor.setPeriodicFramePeriod(PeriodicFrame.kStatus2, (int) (1000.0 / odometryFrequency));
turnMotor.setPeriodicFramePeriod(PeriodicFrame.kStatus2, (int) (1000.0 / odometryFrequency));

if (driveMotor.burnFlash().equals(REVLibError.kOk)
&& turnMotor.burnFlash().equals(REVLibError.kOk)) break;
}

driveMotor.burnFlash();
turnMotor.burnFlash();

driveMotor.setCANTimeout(0);
turnMotor.setCANTimeout(0);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ public class GenerateTrajectories {
public static void main(String[] args) {
Constants.disableHAL();
var channel =
Grpc.newChannelBuilder("10.63.28.184:56328", InsecureChannelCredentials.create()).build();
Grpc.newChannelBuilder("127.0.0.1:56328", InsecureChannelCredentials.create()).build();
var service = VehicleTrajectoryServiceGrpc.newBlockingStub(channel);

VehicleModel model =
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,23 +5,26 @@
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import lombok.Getter;
import lombok.RequiredArgsConstructor;
import lombok.Setter;
import org.littletonrobotics.frc2024.FieldConstants;
import org.littletonrobotics.frc2024.RobotState;
import org.littletonrobotics.frc2024.subsystems.superstructure.arm.Arm;
import org.littletonrobotics.frc2024.subsystems.superstructure.feeder.Feeder;
import org.littletonrobotics.frc2024.subsystems.superstructure.flywheels.Flywheels;
import org.littletonrobotics.frc2024.subsystems.superstructure.intake.Intake;
import org.littletonrobotics.frc2024.util.LoggedTunableNumber;
import org.littletonrobotics.junction.AutoLogOutput;
import org.littletonrobotics.junction.Logger;

@RequiredArgsConstructor
public class Superstructure extends SubsystemBase {
private static LoggedTunableNumber armIdleSetpointDegrees =
new LoggedTunableNumber("Superstructure/ArmIdleSetpointDegrees", 20.0);
private static LoggedTunableNumber armStationIntakeSetpointDegrees =
new LoggedTunableNumber("Superstructure/ArmStationIntakeSetpointDegrees", 45.0);
private static LoggedTunableNumber armIntakeSetpointDegrees =
new LoggedTunableNumber("Superstructure/ArmIntakeDegrees", 20.0);
new LoggedTunableNumber("Superstructure/ArmIntakeDegrees", 40.0);
private static LoggedTunableNumber yCompensation =
new LoggedTunableNumber("Superstructure/CompensationInches", 6.0);
private static LoggedTunableNumber followThroughTime =
Expand All @@ -30,25 +33,34 @@ public class Superstructure extends SubsystemBase {
public enum SystemState {
PREPARE_SHOOT,
SHOOT,

PREPARE_INTAKE,
INTAKE,
IDLE,
STATION_INTAKE
STATION_INTAKE,
REVERSE_INTAKE,
IDLE
}

public enum GamepieceState {
NO_GAMEPIECE,

HOLDING_SHOOTER,

HOLDING_BACKPACK
}

@Getter private SystemState currentState = SystemState.IDLE;
@Getter @Setter private SystemState goalState = SystemState.IDLE;

@Getter @Setter private GamepieceState gamepieceState = GamepieceState.NO_GAMEPIECE;

private final Arm arm;
private final Flywheels flywheels;
private final Feeder feeder;
private final Intake intake;

private final Timer followThroughTimer = new Timer();

public Superstructure(Arm arm, Flywheels flywheels, Feeder feeder) {
this.arm = arm;
this.flywheels = flywheels;
this.feeder = feeder;
}

@Override
public void periodic() {
switch (goalState) {
Expand All @@ -65,6 +77,7 @@ public void periodic() {
currentState = SystemState.IDLE;
}
}
case STATION_INTAKE -> currentState = SystemState.STATION_INTAKE;
case INTAKE -> currentState = SystemState.INTAKE;
case PREPARE_SHOOT -> currentState = SystemState.PREPARE_SHOOT;
case SHOOT -> {
Expand All @@ -83,16 +96,24 @@ public void periodic() {
arm.setSetpoint(Rotation2d.fromDegrees(armIdleSetpointDegrees.get()));
flywheels.setGoal(Flywheels.Goal.IDLE);
feeder.setGoal(Feeder.Goal.IDLE);
intake.setGoal(Intake.Goal.IDLE);
}
case INTAKE -> {
arm.setSetpoint(Rotation2d.fromDegrees(armIntakeSetpointDegrees.get()));
flywheels.setGoal(Flywheels.Goal.IDLE);
feeder.setGoal(Feeder.Goal.INTAKING);
intake.setGoal(Intake.Goal.INTAKE);
}
case STATION_INTAKE -> {
arm.setSetpoint(Rotation2d.fromDegrees(armStationIntakeSetpointDegrees.get()));
flywheels.setGoal(Flywheels.Goal.INTAKING);
feeder.setGoal(Feeder.Goal.REVERSE_INTAKING);
intake.setGoal(Intake.Goal.IDLE);
}
case REVERSE_INTAKE -> {
arm.setSetpoint(Rotation2d.fromDegrees(armIntakeSetpointDegrees.get()));
feeder.setGoal(Feeder.Goal.REVERSE_INTAKING);
intake.setGoal(Intake.Goal.REVERSE_INTAKE);
}
case PREPARE_SHOOT -> {
var aimingParams = RobotState.getInstance().getAimingParameters();
Expand All @@ -103,9 +124,11 @@ public void periodic() {
+ Units.inchesToMeters(yCompensation.get())));
flywheels.setGoal(Flywheels.Goal.SHOOTING);
feeder.setGoal(Feeder.Goal.IDLE);
intake.setGoal(Intake.Goal.IDLE);
}
case SHOOT -> {
feeder.setGoal(Feeder.Goal.FEEDING);
gamepieceState = GamepieceState.NO_GAMEPIECE;
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ public ArmIOKrakenFOC() {
leaderInverted ? InvertedValue.Clockwise_Positive : InvertedValue.CounterClockwise_Positive;
leaderConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake;
leaderConfig.Feedback.FeedbackRemoteSensorID = armEncoderID;
leaderConfig.Feedback.FeedbackSensorSource = FeedbackSensorSourceValue.FusedCANcoder;
leaderConfig.Feedback.FeedbackSensorSource = FeedbackSensorSourceValue.SyncCANcoder;
leaderConfig.Feedback.SensorToMechanismRatio = 1.0;
leaderConfig.Feedback.RotorToSensorRatio = reduction;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,9 +4,15 @@
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import lombok.Getter;
import lombok.Setter;
import org.littletonrobotics.frc2024.util.LoggedTunableNumber;
import org.littletonrobotics.junction.Logger;

public class Feeder extends SubsystemBase {
private static final LoggedTunableNumber intakeVoltage =
new LoggedTunableNumber("Feeder/IntakeVoltage", 4.0);
private static final LoggedTunableNumber feedVoltage =
new LoggedTunableNumber("Feeder/FeedVoltage", 12.0);

private final FeederIO io;
private FeederIOInputsAutoLogged inputs = new FeederIOInputsAutoLogged();

Expand Down Expand Up @@ -37,15 +43,19 @@ public void periodic() {
} else {
switch (goal) {
case IDLE -> runVolts(0.0);
case FEEDING -> runVolts(12.0);
case INTAKING -> runVolts(6.0);
case REVERSE_INTAKING -> runVolts(-6.0);
case FEEDING -> runVolts(feedVoltage.get());
case INTAKING -> runVolts(intakeVoltage.get());
case REVERSE_INTAKING -> runVolts(-intakeVoltage.get());
}
}

Logger.recordOutput("Feeder/Goal", goal);
}

public boolean hasGamepiece() {
return inputs.outputCurrent >= 40.0;
}

public void runVolts(double volts) {
io.runVolts(volts);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@ public class FeederIOSparkFlex implements FeederIO {
public FeederIOSparkFlex() {
motor = new CANSparkFlex(id, CANSparkBase.MotorType.kBrushless);

motor.setSmartCurrentLimit(80);
motor.setInverted(inverted);
motor.setIdleMode(CANSparkBase.IdleMode.kBrake);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,9 +28,9 @@ public class Flywheels extends SubsystemBase {
new LoggedTunableNumber("Superstructure/IdleRightRPM", 200.0);

private static LoggedTunableNumber intakingLeftRPM =
new LoggedTunableNumber("Superstructure/IdleLeftRPM", 2000.0);
new LoggedTunableNumber("Superstructure/IntakingLeftRPM", -2000.0);
private static LoggedTunableNumber intakingRightRPM =
new LoggedTunableNumber("Superstructure/IdleRightRPM", -2000.0);
new LoggedTunableNumber("Superstructure/IntakingRightRPM", -2000.0);
private static final LoggedTunableNumber shooterTolerance =
new LoggedTunableNumber("Flywheels/ToleranceRPM", shooterToleranceRPM);

Expand Down
Original file line number Diff line number Diff line change
@@ -1,81 +1,40 @@
package org.littletonrobotics.frc2024.subsystems.superstructure.intake;

import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import lombok.Getter;
import lombok.Setter;
import org.littletonrobotics.frc2024.util.LoggedTunableNumber;
import org.littletonrobotics.junction.Logger;
import org.littletonrobotics.junction.networktables.LoggedDashboardNumber;

public class Intake extends SubsystemBase {
private final LoggedDashboardNumber intakeVoltage =
new LoggedDashboardNumber("Intake/intakeVoltage", 8.0);
private final LoggedTunableNumber intakeVolts =
new LoggedTunableNumber("Intake/intakeVoltage", 8.0);
private final LoggedTunableNumber ejectVolts = new LoggedTunableNumber("Intake/ejectVolts", -2.0);
private final IntakeIO io;
private final IntakeIOInputsAutoLogged inputs = new IntakeIOInputsAutoLogged();

private boolean intake = false;
private boolean eject = false;
public enum Goal {
IDLE,
INTAKE,
REVERSE_INTAKE
}

@Setter @Getter Goal goal = Goal.IDLE;

public Intake(IntakeIO io) {
System.out.println("[Init] Creating Intake");
this.io = io;
// TODO: test if this is needed
io.setBrakeMode(false);
}

@Override
public void periodic() {
io.updateInputs(inputs);
Logger.processInputs("Intake", inputs);

if (DriverStation.isDisabled()) {
stop();
} else {
if (intake) {
io.setVoltage(intakeVoltage.get());
} else if (eject) {
io.setVoltage(-intakeVoltage.get());
}
switch (goal) {
case IDLE -> io.stop();
case INTAKE -> io.runVolts(intakeVolts.get());
case REVERSE_INTAKE -> io.runVolts(ejectVolts.get());
}
}

public boolean intaking() {
return intake;
}

public boolean ejecting() {
return eject;
}

public boolean running() {
return eject || intake;
}

private void intake() {
intake = true;
eject = false;
}

private void eject() {
eject = true;
intake = false;
}

private void stop() {
intake = false;
eject = false;
io.stop();
}

public Command intakeCommand() {
return Commands.runOnce(this::intake);
}

public Command ejectCommand() {
return Commands.runOnce(this::eject);
}

public Command stopCommand() {
return Commands.runOnce(this::stop);
}
}
Loading

0 comments on commit ecf86d0

Please sign in to comment.