Skip to content
Open
1 change: 1 addition & 0 deletions 2025-training
Submodule 2025-training added at bc380f
17 changes: 16 additions & 1 deletion src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,9 +4,15 @@

package frc.robot;

import dev.doglog.DogLog;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.CommandScheduler;
import edu.wpi.first.wpilibj2.command.InstantCommand;
import frc.robot.Constants.OperatorConstants;
import frc.robot.subsystems.Piper;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import edu.wpi.first.wpilibj2.command.button.Trigger;

/**
* The VM is configured to automatically run this class, and to call the functions corresponding to
Expand All @@ -18,6 +24,10 @@ public class Robot extends TimedRobot {
private Command m_autonomousCommand;

private RobotContainer m_robotContainer;
private Piper m_piper = Piper.getInstance();

private final CommandXboxController m_driverController =
new CommandXboxController(OperatorConstants.kDriverControllerPort);

/**
* This function is run when the robot is first started up and should be used for any
Expand All @@ -28,6 +38,8 @@ public void robotInit() {
// Instantiate our RobotContainer. This will perform all our button bindings, and put our
// autonomous chooser on the dashboard.
m_robotContainer = new RobotContainer();
// DogLog.setOptions(new DogLogOptions().withNtPublish(true).withCaptureDs(true).withLogExtras(true));

}

/**
Expand Down Expand Up @@ -81,7 +93,10 @@ public void teleopInit() {

/** This function is called periodically during operator control. */
@Override
public void teleopPeriodic() {}
public void teleopPeriodic() {
m_driverController.rightBumper().onTrue(new InstantCommand(() -> m_piper.increaseFF()));
m_driverController.leftBumper().onTrue(new InstantCommand(() -> m_piper.decreaseFF()));
}

@Override
public void testInit() {
Expand Down
24 changes: 15 additions & 9 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,9 @@

import frc.robot.Constants.OperatorConstants;
import frc.robot.commands.Autos;
import frc.robot.commands.ExampleCommand;
import frc.robot.subsystems.ExampleSubsystem;
import frc.robot.commands.Intake;
import frc.robot.commands.Shooter;
import frc.robot.subsystems.Piper;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import edu.wpi.first.wpilibj2.command.button.Trigger;
Expand All @@ -20,15 +21,19 @@
*/
public class RobotContainer {
// The robot's subsystems and commands are defined here...
private final ExampleSubsystem m_exampleSubsystem = new ExampleSubsystem();

// Replace with CommandPS4Controller or CommandJoystick if needed
private final CommandXboxController m_driverController =
new CommandXboxController(OperatorConstants.kDriverControllerPort);

private final Piper piper = Piper.getInstance();


/** The container for the robot. Contains subsystems, OI devices, and commands. */
public RobotContainer() {
// Configure the trigger bindings
m_driverController.rightTrigger().whileTrue(new Intake(piper));
m_driverController.leftTrigger().whileTrue(new Shooter(piper));
configureBindings();
}

Expand All @@ -43,12 +48,12 @@ public RobotContainer() {
*/
private void configureBindings() {
// Schedule `ExampleCommand` when `exampleCondition` changes to `true`
new Trigger(m_exampleSubsystem::exampleCondition)
.onTrue(new ExampleCommand(m_exampleSubsystem));
// new Trigger(m_exampleSubsystem::exampleCondition)
// .onTrue(new ExampleCommand(m_exampleSubsystem));

// Schedule `exampleMethodCommand` when the Xbox controller's B button is pressed,
// cancelling on release.
m_driverController.b().whileTrue(m_exampleSubsystem.exampleMethodCommand());
// // Schedule `exampleMethodCommand` when the Xbox controller's B button is pressed,
// // cancelling on release.
// m_driverController.b().whileTrue(m_exampleSubsystem.exampleMethodCommand());
}

/**
Expand All @@ -57,7 +62,8 @@ private void configureBindings() {
* @return the command to run in autonomous
*/
public Command getAutonomousCommand() {
return null;
// An example command will be run in autonomous
return Autos.exampleAuto(m_exampleSubsystem);
// return Autos.exampleAuto(m_exampleSubsystem);
}
}
4 changes: 0 additions & 4 deletions src/main/java/frc/robot/commands/Autos.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,15 +4,11 @@

package frc.robot.commands;

import frc.robot.subsystems.ExampleSubsystem;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;

public final class Autos {
/** Example static factory for an autonomous command. */
public static Command exampleAuto(ExampleSubsystem subsystem) {
return Commands.sequence(subsystem.exampleMethodCommand(), new ExampleCommand(subsystem));
}

private Autos() {
throw new UnsupportedOperationException("This is a utility class!");
Expand Down
52 changes: 52 additions & 0 deletions src/main/java/frc/robot/commands/Intake.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,52 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.

package frc.robot.commands;
import frc.robot.subsystems.Piper;
import dev.doglog.DogLog;
import edu.wpi.first.wpilibj2.command.Command;

/** An example command that uses an example subsystem. */
public class Intake extends Command {
@SuppressWarnings({"PMD.UnusedPrivateField", "PMD.SingularField"})
private final Piper m_piper;

/**
* Creates a new ExampleCommand.
*
* @param subsystem The subsystem used by this command.
*/
public Intake(Piper piper) {
m_piper = piper;
// Use addRequirements() here to declare subsystem dependencies.
addRequirements(piper);
}

// Called when the command is initially scheduled.
@Override
public void initialize() {
}

// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
double speed = 90;
//m_piper.spinShooter(speed);
m_piper.spinIntake(speed);
m_piper.spinPreShooter(speed);
}

// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
m_piper.stopIntake();
m_piper.stopPreShooter();
}

// Returns true when the command should end.
@Override
public boolean isFinished() {
return m_piper.isNotesThere();
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -4,20 +4,20 @@

package frc.robot.commands;

import frc.robot.subsystems.ExampleSubsystem;
import frc.robot.subsystems.Piper;
import edu.wpi.first.wpilibj2.command.Command;

/** An example command that uses an example subsystem. */
public class ExampleCommand extends Command {
public class PiperCommand extends Command {
@SuppressWarnings({"PMD.UnusedPrivateField", "PMD.SingularField"})
private final ExampleSubsystem m_subsystem;
private final Piper m_subsystem;

/**
* Creates a new ExampleCommand.
*
* @param subsystem The subsystem used by this command.
*/
public ExampleCommand(ExampleSubsystem subsystem) {
public PiperCommand(Piper subsystem) {
m_subsystem = subsystem;
// Use addRequirements() here to declare subsystem dependencies.
addRequirements(subsystem);
Expand Down
51 changes: 51 additions & 0 deletions src/main/java/frc/robot/commands/Shooter.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.

package frc.robot.commands;
import frc.robot.subsystems.Piper;
import dev.doglog.DogLog;
import edu.wpi.first.wpilibj2.command.Command;

/** An example command that uses an example subsystem. */
public class Shooter extends Command {
@SuppressWarnings({"PMD.UnusedPrivateField", "PMD.SingularField"})
private final Piper m_piper;

/**
* Creates a new ExampleCommand.
*
* @param subsystem The subsystem used by this command.
*/
public Shooter(Piper piper) {
m_piper = piper;
// Use addRequirements() here to declare subsystem dependencies.
addRequirements(piper);
}

// Called when the command is initially scheduled.
@Override
public void initialize() {
}

// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
double speed = 50;
m_piper.spinShooter(speed);
m_piper.spinPreShooter(speed/2);
}

// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
m_piper.stopShooter();
m_piper.stopPreShooter();
}

// Returns true when the command should end.
@Override
public boolean isFinished() {
return !(m_piper.isNotesThere());
}
}
47 changes: 0 additions & 47 deletions src/main/java/frc/robot/subsystems/ExampleSubsystem.java

This file was deleted.

Loading