Skip to content

Commit

Permalink
Kitbot ready!
Browse files Browse the repository at this point in the history
  • Loading branch information
suryatho committed Jan 16, 2024
1 parent d9b4c64 commit 4c6de5a
Show file tree
Hide file tree
Showing 5 changed files with 14 additions and 15 deletions.
5 changes: 4 additions & 1 deletion src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@

import edu.wpi.first.wpilibj.RobotBase;
import frc.robot.util.Alert;
import java.util.Map;

/**
* The Constants class provides a convenient place for teams to hold robot-wide numerical or boolean
Expand All @@ -27,7 +28,7 @@
public final class Constants {
public static final int loopPeriodMs = 20;
private static RobotType robotType = RobotType.KITBOT;
public static final boolean tuningMode = true;
public static final boolean tuningMode = false;
public static final boolean characterizationMode = false;

private static boolean invalidRobotAlertSent = false;
Expand All @@ -49,6 +50,8 @@ public static Mode getMode() {
};
}

public static final Map<RobotType, String> logFolders = Map.of(RobotType.KITBOT, "/media/sda1/");

public enum Mode {
/** Running on a real robot. */
REAL,
Expand Down
3 changes: 2 additions & 1 deletion src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,8 @@ public void robotInit() {
switch (Constants.getMode()) {
case REAL:
// Running on a real robot, log to a USB stick ("/U/logs")
Logger.addDataReceiver(new WPILOGWriter());
String folder = Constants.logFolders.get(Constants.getRobot());
Logger.addDataReceiver(new WPILOGWriter(folder));
Logger.addDataReceiver(new NT4Publisher());
break;

Expand Down
11 changes: 3 additions & 8 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -24,12 +24,7 @@
import frc.robot.commands.DriveCommands;
import frc.robot.commands.DriveTrajectory;
import frc.robot.commands.FeedForwardCharacterization;
import frc.robot.subsystems.drive.Drive;
import frc.robot.subsystems.drive.GyroIO;
import frc.robot.subsystems.drive.GyroIOPigeon2;
import frc.robot.subsystems.drive.ModuleIO;
import frc.robot.subsystems.drive.ModuleIOSim;
import frc.robot.subsystems.drive.ModuleIOSparkMax;
import frc.robot.subsystems.drive.*;
import frc.robot.subsystems.kitbotshooter.*;
import frc.robot.util.trajectory.ChoreoTrajectoryReader;
import frc.robot.util.trajectory.Trajectory;
Expand Down Expand Up @@ -73,8 +68,7 @@ public RobotContainer() {
new ModuleIOSparkMax(1),
new ModuleIOSparkMax(2),
new ModuleIOSparkMax(3));
shooter =
new KitbotShooter(new KitbotFlywheelIOSparkMax(), new KitbotFeederIOSparkMax());
shooter = new KitbotShooter(new KitbotFlywheelIO() {}, new KitbotFeederIO() {});
}
}
}
Expand Down Expand Up @@ -165,6 +159,7 @@ private void configureButtonBindings() {
new Pose2d(drive.getPose().getTranslation(), new Rotation2d())),
drive)
.ignoringDisable(true));
controller.button(8).onTrue(Commands.runOnce(() -> drive.setPose(new Pose2d())));
controller
.a()
.whileTrue(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@

/** IO implementation for Pigeon2 */
public class GyroIOPigeon2 implements GyroIO {
private final Pigeon2 pigeon = new Pigeon2(20);
private final Pigeon2 pigeon = new Pigeon2(0);
private final StatusSignal<Double> yaw = pigeon.getYaw();
private final Queue<Double> yawPositionQueue;
private final StatusSignal<Double> yawVelocity = pigeon.getAngularVelocityZWorld();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -59,25 +59,25 @@ public ModuleIOSparkMax(int index) {
driveSparkMax = new CANSparkMax(15, MotorType.kBrushless);
turnSparkMax = new CANSparkMax(11, MotorType.kBrushless);
turnAbsoluteEncoder = new AnalogInput(0);
absoluteEncoderOffset = new Rotation2d(0.0); // MUST BE CALIBRATED
absoluteEncoderOffset = new Rotation2d(-0.036); // MUST BE CALIBRATED
break;
case 1:
driveSparkMax = new CANSparkMax(12, MotorType.kBrushless);
turnSparkMax = new CANSparkMax(9, MotorType.kBrushless);
turnAbsoluteEncoder = new AnalogInput(1);
absoluteEncoderOffset = new Rotation2d(0.0); // MUST BE CALIBRATED
absoluteEncoderOffset = new Rotation2d(1.0185); // MUST BE CALIBRATED
break;
case 2:
driveSparkMax = new CANSparkMax(14, MotorType.kBrushless);
turnSparkMax = new CANSparkMax(10, MotorType.kBrushless);
turnAbsoluteEncoder = new AnalogInput(2);
absoluteEncoderOffset = new Rotation2d(0.0); // MUST BE CALIBRATED
absoluteEncoderOffset = new Rotation2d(1.0705); // MUST BE CALIBRATED
break;
case 3:
driveSparkMax = new CANSparkMax(13, MotorType.kBrushless);
turnSparkMax = new CANSparkMax(8, MotorType.kBrushless);
turnAbsoluteEncoder = new AnalogInput(3);
absoluteEncoderOffset = new Rotation2d(0.0); // MUST BE CALIBRATED
absoluteEncoderOffset = new Rotation2d(0.7465); // MUST BE CALIBRATED
break;
default:
throw new RuntimeException("Invalid module index");
Expand Down

0 comments on commit 4c6de5a

Please sign in to comment.