Skip to content

Commit

Permalink
Browse files Browse the repository at this point in the history
…ateRobotCode into AK-files
  • Loading branch information
Vignesh1234587 committed Dec 6, 2024
2 parents 43e6dba + e1110fd commit 980db09
Show file tree
Hide file tree
Showing 7 changed files with 580 additions and 214 deletions.
93 changes: 40 additions & 53 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,12 @@

package frc.robot;

import org.littletonrobotics.junction.networktables.LoggedDashboardChooser;
import org.littletonrobotics.junction.networktables.LoggedDashboardNumber;

import com.pathplanner.lib.auto.AutoBuilder;
import com.pathplanner.lib.auto.NamedCommands;

import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.wpilibj.GenericHID;
Expand All @@ -23,24 +28,21 @@
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine;
import frc.robot.commands.DriveCommands;
<<<<<<< Updated upstream
=======
import frc.robot.generated.TunerConstants;
>>>>>>> Stashed changes
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.ModuleIOTalonFX;
<<<<<<< Updated upstream
import frc.robot.subsystems.flywheel.Flywheel;
import frc.robot.subsystems.flywheel.FlywheelIO;
import frc.robot.subsystems.flywheel.FlywheelIOSim;
import frc.robot.subsystems.flywheel.FlywheelIOSparkMax;
=======
>>>>>>> Stashed changes
import org.littletonrobotics.junction.networktables.LoggedDashboardChooser;
import frc.robot.subsystems.vision.Vision;
import static frc.robot.subsystems.vision.VisionConstants.camera0Name;
import static frc.robot.subsystems.vision.VisionConstants.camera1Name;
import frc.robot.subsystems.vision.VisionIO;
import frc.robot.subsystems.vision.VisionIOLimelight;

/**
* This class is where the bulk of the robot should be declared. Since Command-based is a
Expand All @@ -50,66 +52,60 @@
*/
public class RobotContainer {
// Subsystems
<<<<<<< Updated upstream
public static Drive drive;
private final Flywheel flywheel;
=======
private final Drive drive;
>>>>>>> Stashed changes
private final Vision vision;

// Controller
private final CommandXboxController controller = new CommandXboxController(0);

// Dashboard inputs
private final LoggedDashboardChooser<Command> autoChooser;
private final LoggedDashboardNumber flywheelSpeedInput =
new LoggedDashboardNumber("Flywheel Speed", 1500.0);

/** The container for the robot. Contains subsystems, OI devices, and commands. */
public RobotContainer() {
switch (Constants.currentMode) {
switch (physicalConstants.currentMode) {
case REAL:
// Real robot, instantiate hardware IO implementations
drive =
new Drive(
<<<<<<< Updated upstream
new GyroIOPigeon2(false),
new ModuleIOTalonFX(0),
new ModuleIOTalonFX(1),
new ModuleIOTalonFX(2),
new ModuleIOTalonFX(3));

flywheel = new Flywheel(new FlywheelIOSparkMax());
vision =
new Vision(
drive::addVisionMeasurement,
new VisionIOLimelight(camera0Name, drive::getRotation),
new VisionIOLimelight(camera1Name, drive::getRotation));

// drive = new Drive(
// new GyroIOPigeon2(true),
// new ModuleIOTalonFX(0),
// new ModuleIOTalonFX(1),
// new ModuleIOTalonFX(2),
// new ModuleIOTalonFX(3));
// flywheel = new Flywheel(new FlywheelIOTalonFX());
=======
new GyroIOPigeon2(),
new ModuleIOTalonFX(TunerConstants.FrontLeft),
new ModuleIOTalonFX(TunerConstants.FrontRight),
new ModuleIOTalonFX(TunerConstants.BackLeft),
new ModuleIOTalonFX(TunerConstants.BackRight));
>>>>>>> Stashed changes
break;

case SIM:
// Sim robot, instantiate physics sim IO implementations
drive =
new Drive(
new GyroIO() {},
<<<<<<< Updated upstream
new ModuleIOSim(),
new ModuleIOSim(),
new ModuleIOSim(),
new ModuleIOSim());
vision = new Vision(drive::addVisionMeasurement, new VisionIO() {}, new VisionIO() {});

flywheel = new Flywheel(new FlywheelIOSim());
=======
new ModuleIOSim(TunerConstants.FrontLeft),
new ModuleIOSim(TunerConstants.FrontRight),
new ModuleIOSim(TunerConstants.BackLeft),
new ModuleIOSim(TunerConstants.BackRight));
>>>>>>> Stashed changes

break;

default:
Expand All @@ -121,21 +117,20 @@ public RobotContainer() {
new ModuleIO() {},
new ModuleIO() {},
new ModuleIO() {});
<<<<<<< Updated upstream
flywheel = new Flywheel(new FlywheelIO() {});
=======
>>>>>>> Stashed changes
vision = new Vision(drive::addVisionMeasurement, new VisionIO() {}, new VisionIO() {});
break;
}

// Set up auto routines
NamedCommands.registerCommand(
"Run Flywheel",
Commands.startEnd(
() -> flywheel.runVelocity(flywheelSpeedInput.get()), flywheel::stop, flywheel)
.withTimeout(5.0));
autoChooser = new LoggedDashboardChooser<>("Auto Choices", AutoBuilder.buildAutoChooser());

// Set up SysId routines
autoChooser.addOption(
"Drive Wheel Radius Characterization", DriveCommands.wheelRadiusCharacterization(drive));
autoChooser.addOption(
"Drive Simple FF Characterization", DriveCommands.feedforwardCharacterization(drive));
autoChooser.addOption(
"Drive SysId (Quasistatic Forward)",
drive.sysIdQuasistatic(SysIdRoutine.Direction.kForward));
Expand All @@ -146,6 +141,16 @@ public RobotContainer() {
"Drive SysId (Dynamic Forward)", drive.sysIdDynamic(SysIdRoutine.Direction.kForward));
autoChooser.addOption(
"Drive SysId (Dynamic Reverse)", drive.sysIdDynamic(SysIdRoutine.Direction.kReverse));
autoChooser.addOption(
"Flywheel SysId (Quasistatic Forward)",
flywheel.sysIdQuasistatic(SysIdRoutine.Direction.kForward));
autoChooser.addOption(
"Flywheel SysId (Quasistatic Reverse)",
flywheel.sysIdQuasistatic(SysIdRoutine.Direction.kReverse));
autoChooser.addOption(
"Flywheel SysId (Dynamic Forward)", flywheel.sysIdDynamic(SysIdRoutine.Direction.kForward));
autoChooser.addOption(
"Flywheel SysId (Dynamic Reverse)", flywheel.sysIdDynamic(SysIdRoutine.Direction.kReverse));

// Configure the button bindings
configureButtonBindings();
Expand All @@ -158,28 +163,13 @@ public RobotContainer() {
* edu.wpi.first.wpilibj2.command.button.JoystickButton}.
*/
private void configureButtonBindings() {
// Default command, normal field-relative drive
drive.setDefaultCommand(
DriveCommands.joystickDrive(
drive,
() -> -controller.getLeftY(),
() -> -controller.getLeftX(),
() -> -controller.getRightX()));

// Lock to 0° when A button is held
controller
.a()
.whileTrue(
DriveCommands.joystickDriveAtAngle(
drive,
() -> -controller.getLeftY(),
() -> -controller.getLeftX(),
() -> new Rotation2d()));

// Switch to X pattern when X button is pressed
controller.x().onTrue(Commands.runOnce(drive::stopWithX, drive));

// Reset gyro to 0° when B button is pressed
controller
.b()
.onTrue(
Expand All @@ -189,14 +179,11 @@ private void configureButtonBindings() {
new Pose2d(drive.getPose().getTranslation(), new Rotation2d())),
drive)
.ignoringDisable(true));
<<<<<<< Updated upstream
controller
.a()
.whileTrue(
Commands.startEnd(
() -> flywheel.runVelocity(flywheelSpeedInput.get()), flywheel::stop, flywheel));
=======
>>>>>>> Stashed changes
}

/**
Expand Down
5 changes: 2 additions & 3 deletions src/main/java/frc/robot/physicalConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -45,8 +45,7 @@ public static class IntakeConstants {
public static final boolean CURRENT_LIMIT_ENABLED = true;
}

public static final class shooterConstants {
}
public static final class shooterConstants {}

public static class ElevatorConstants {
public static final double CURRENT_LIMIT = 40.0;
Expand All @@ -70,7 +69,7 @@ public static final class PivotConstants {
public static final double REDUCTION =
(15.0 / 1.0) * (34.0 / 24.0) * (24.0 / 18.0) * (50.0 / 14.0);
public static final double STOW_SETPOINT_DEG = 50.7;

public static final double PIVOT_ZERO_ANGLE = 59;
}

Expand Down
Loading

0 comments on commit 980db09

Please sign in to comment.