Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
9 changes: 9 additions & 0 deletions motor-ids.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
Intake
Roller 2
Extension 1
Indexer
Main: 4
Accelerator: 3
Shooter
Flywheel - x3: 5,6,7
Hood: 8
7 changes: 4 additions & 3 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,6 @@
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.CommandScheduler;
import frc.robot.statemachines.LaunchState;
import frc.robot.statemachines.ShiftState;

/**
Expand Down Expand Up @@ -106,13 +105,15 @@ public void disabledPeriodic() {}
/** This autonomous runs the autonomous command selected by your {@link RobotContainer} class. */
@Override
public void autonomousInit() {
/*
m_autonomousCommand = m_robotContainer.getAutonomousCommand();
LaunchState.getInstance().setTargetPose3d(Constants.FieldConstants.getHubTarget());

// schedule the autonomous command
if (m_autonomousCommand != null) {
CommandScheduler.getInstance().schedule(m_autonomousCommand);
}
*/
}

/** This function is called periodically during autonomous. */
Expand Down Expand Up @@ -140,8 +141,8 @@ public void testInit() {
CommandScheduler.getInstance().cancelAll();

SignalLogger.stop();
m_robotContainer.removeSubsystemDefaultCommands();
m_robotContainer.configureTestBindings();
// m_robotContainer.removeSubsystemDefaultCommands();
// m_robotContainer.configureTestBindings();
}

/** This function is called periodically during test mode. */
Expand Down
27 changes: 17 additions & 10 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,7 @@ public class RobotContainer {
private final Telemetry logger = new Telemetry(DriveConstants.MAX_DRIVE_SPEED);

private final CommandXboxController driverJoystick = new CommandXboxController(0);

private final CommandXboxController operatorJoystick = new CommandXboxController(1);

@Logged(name = "Drivetrain")
Expand All @@ -50,9 +51,6 @@ public class RobotContainer {
@Logged(name = "Shooter")
public final ShooterSubsystem shooter = new ShooterSubsystem();

// @Logged(name = "Climber")
// public final ClimberSubsystem climber = new ClimberSubsystem();

@Logged(name = "Vision")
public final VisionSubsystem vision = new VisionSubsystem();

Expand All @@ -63,6 +61,7 @@ public class RobotContainer {
private final DriveState driveState = DriveState.getInstance();
private final LaunchState launchState = LaunchState.getInstance();

/*
private final Command driveAndLaunchCommand =
drivetrain
.applyRequest(() -> getDriveAndLaunchRequest())
Expand All @@ -82,13 +81,14 @@ public class RobotContainer {
.stopFullIndexingNoPID()
.andThen(shooter.stopFlywheelCommand())
.andThen(shooter.stowHood());
*/

private final SendableChooser<Command> autoChooser;

public RobotContainer() {
NamedCommands.registerCommand("Seed", drivetrain.runOnce(drivetrain::seedFieldCentric));
NamedCommands.registerCommand("AutonShoot", autonShootCommand);
NamedCommands.registerCommand("StopShot", stopShotCommand);
// NamedCommands.registerCommand("AutonShoot", autonShootCommand);
// NamedCommands.registerCommand("StopShot", stopShotCommand);
NamedCommands.registerCommand("StopRoller", intake.stopRollerNoPID());
NamedCommands.registerCommand(
"Collect Intake",
Expand All @@ -103,7 +103,6 @@ public RobotContainer() {
NamedCommands.registerCommand(
"HP Reload", new WaitCommand(IntakePreferences.outpostReloadWait.getValue()));
autoChooser = AutoBuilder.buildAutoChooser("Auto Chooser");
autoChooser.addOption("Auton Shoot", autonShootCommand);
SmartDashboard.putData("Auto Mode", autoChooser);

// Idle while the robot is disabled. This ensures the configured
Expand Down Expand Up @@ -166,6 +165,7 @@ public void removeSubsystemDefaultCommands() {
drivetrain.removeDefaultCommand();
}

/*
public void configureTestBindings() {
// Idle while the robot is disabled. This ensures the configured
// neutral mode is applied to the drive motors while disabled.
Expand Down Expand Up @@ -202,9 +202,9 @@ public void configureTestBindings() {

driverJoystick.x().onTrue(intake.spinRollerCommand()).onFalse(intake.stopRollerCommand());
}
*/

public void configureTeleopBindings() {

driverJoystick
.rightBumper()
// .whileTrue(intake.setExtendNoPID())
Expand All @@ -218,6 +218,10 @@ public void configureTeleopBindings() {
.andThen(intake.setIntakeExtensionCommand(IntakeConstants.INTAKE_REVERSE_LIMIT))
.withName("Stow Intake"));

// stop the roller without retracting.
driverJoystick.x().onTrue(intake.stopRollerNoPID());

/*
// outtake fuel. don't retract when done.
driverJoystick
.b()
Expand All @@ -230,9 +234,6 @@ public void configureTeleopBindings() {
.onFalse(
intake.stopRollerNoPID().andThen(indexer.stopIndexerNoPID()).withName("Stop Roller"));

// stop the roller without retracting.
driverJoystick.x().onTrue(intake.stopRollerNoPID());

operatorJoystick
.rightTrigger()
.whileTrue(
Expand All @@ -256,6 +257,7 @@ public void configureTeleopBindings() {
.rightBumper()
.whileTrue(shooter.spinFlywheelPostCommand())
.onFalse(shooter.stopFlywheelCommand().andThen(shooter.stowHood()));
*/

// Reset the field-centric heading on start button press.
driverJoystick
Expand Down Expand Up @@ -301,6 +303,11 @@ public void configureTeleopBindings() {
.manualRumbleCommand(driverJoystick.getHID())
.withName("Rumble Driver Controller"));

operatorJoystick.rightTrigger().whileTrue(indexer.startFullIndexingNoPID());
operatorJoystick.a().onTrue(shooter.setHoodTargetCommand());
operatorJoystick.leftBumper().onTrue(shooter.setFlywheelOutputCommand());
operatorJoystick.rightBumper().onTrue(shooter.stopFlywheelOutputCommand());

drivetrain.registerTelemetry(logger::telemeterize);
}

Expand Down
46 changes: 0 additions & 46 deletions src/main/java/frc/robot/subsystems/climber/ClimberConstants.java

This file was deleted.

This file was deleted.

68 changes: 0 additions & 68 deletions src/main/java/frc/robot/subsystems/climber/ClimberSubsystem.java

This file was deleted.

19 changes: 5 additions & 14 deletions src/main/java/frc/robot/subsystems/indexer/IndexerConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -10,12 +10,10 @@ final class IndexerConstants {

private IndexerConstants() {}

// TODO Replace with real id
protected static final int INDEXER_MOTOR_LEADER_ID = 3;
protected static final int INDEXER_MOTOR_FOLLOWER_ID = 9;
protected static final int ACCELERATOR_MOTOR_ID = 8;
protected static final int INDEXER_MOTOR_LEADER_ID = 4;
protected static final int ACCELERATOR_MOTOR_ID = 3;

// TODO: Tune motor
// TODO: PID tune motor

protected static final double INDEXER_KS = 0;
protected static final double INDEXER_KV = 0;
Expand Down Expand Up @@ -45,20 +43,13 @@ protected static Slot0Configs createAcceleratorMotorSlot0Configs() {
return slot;
}

public static MotorOutputConfigs createLeaderMotorOutputConfigs() {
public static MotorOutputConfigs createIndexerMotorOutputConfigs() {
MotorOutputConfigs newConfigs = new MotorOutputConfigs();
newConfigs.Inverted = InvertedValue.CounterClockwise_Positive;
newConfigs.NeutralMode = NeutralModeValue.Brake;
return newConfigs;
}

public static MotorOutputConfigs createFollowerMotorOutputConfigs() {
MotorOutputConfigs newConfigs = new MotorOutputConfigs();
newConfigs.Inverted = InvertedValue.Clockwise_Positive;
newConfigs.NeutralMode = NeutralModeValue.Brake;
return newConfigs;
}

public static final double INDEXER_CURRENT_LIMIT = 40;

public static CurrentLimitsConfigs createIndexerCurrentLimitsConfigs() {
Expand All @@ -70,7 +61,7 @@ public static CurrentLimitsConfigs createIndexerCurrentLimitsConfigs() {

public static MotorOutputConfigs createAcceleratorMotorOutputsConfigs() {
MotorOutputConfigs newConfigs = new MotorOutputConfigs();
newConfigs.Inverted = InvertedValue.Clockwise_Positive;
newConfigs.Inverted = InvertedValue.CounterClockwise_Positive;
newConfigs.NeutralMode = NeutralModeValue.Brake;
return newConfigs;
}
Expand Down
17 changes: 12 additions & 5 deletions src/main/java/frc/robot/subsystems/indexer/IndexerPreferences.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,21 +6,28 @@ final class IndexerPreferences {

private IndexerPreferences() {}

protected static DoublePreference indexSpeed =
new DoublePreference("Indexer/Index Speed", 0.1); // in rotations per second

protected static DoublePreference indexerPercent =
new DoublePreference("Indexer/Index Percent (for without PID)", 0.1); // in percent

protected static DoublePreference acceleratorPercent =
new DoublePreference("Indexer/Accelerator Percent (for without PID)", 0.1); // in percent

/*
protected static DoublePreference indexSpeed =
new DoublePreference("Indexer/Index Speed (RotationsPS)", 0.1); // in rotations per second

protected static DoublePreference indexerReversePercent =
new DoublePreference("Indexer/Reverse Index Percent (for without PID)", -0.1); // in percent

protected static DoublePreference acceleratorPercent =
new DoublePreference("Indexer/Accelerator Percent (for without PID)", 0.1); // in percent
protected static DoublePreference accelerateSpeed =
new DoublePreference(
"Indexer/Accelerate Speed (RotationsPS)", 0.1); // in rotations per second


protected static DoublePreference indexerRunTime =
new DoublePreference("Indexer/Pulsing Run Time", 2.0); // in seconds

protected static DoublePreference indexerPauseTime =
new DoublePreference("Indexer/Pulsing Pause Time", 0.1); // in seconds
*/
}
Loading
Loading