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
8 changes: 4 additions & 4 deletions src/main/java/org/team157/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -172,20 +172,20 @@ public void robotPeriodic() {
SmartDashboard.putNumber("Match Time", Timer.getMatchTime());
// Gets hub activity status to display on the dashboard.
SmartDashboard.putBoolean("Hub Active?", m_robotContainer.isHubActive());
SmartDashboard.putBoolean("Under Trench?", m_robotContainer.drivetrain.isUnderTrench());
SmartDashboard.putBoolean("Under Trench?", RobotContainer.drivetrain.isUnderTrench());

}

/** This function is called once each time the robot enters Disabled mode. */
@Override
public void disabledInit() {
m_robotContainer.visionSystem.updatePoseEstimation(m_robotContainer.drivetrain);
m_robotContainer.visionSystem.updatePoseEstimation(RobotContainer.drivetrain);
}

@Override
public void disabledPeriodic() {
m_robotContainer.visionSystem.resetPoseEstimation(m_robotContainer.drivetrain);
m_robotContainer.visionSystem.updatePoseEstimation(m_robotContainer.drivetrain);
m_robotContainer.visionSystem.resetPoseEstimation(RobotContainer.drivetrain);
m_robotContainer.visionSystem.updatePoseEstimation(RobotContainer.drivetrain);

}

Expand Down
37 changes: 19 additions & 18 deletions src/main/java/org/team157/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -37,8 +37,10 @@
import org.team157.robot.subsystems.intake.IntakeIOTalonFX;
import org.team157.robot.subsystems.slapdown.Slapdown;
import org.team157.robot.subsystems.slapdown.SlapdownIOTalonFX;
import org.team157.robot.subsystems.turret.TurretSystem;
import org.team157.robot.subsystems.uptake.UptakeSystem;
import org.team157.robot.subsystems.uptake.Uptake;
import org.team157.robot.subsystems.uptake.UptakeIOTalonFX;
import org.team157.robot.subsystems.turret.Turret;
import org.team157.robot.subsystems.turret.TurretIOTalonFX;
import org.team157.robot.subsystems.vision.VisionSystem;

public class RobotContainer {
Expand All @@ -57,21 +59,18 @@ public class RobotContainer {
private final CommandXboxController driverController = new CommandXboxController(0);
private final CommandXboxController operatorController = new CommandXboxController(1);

public final TurretSystem turret;
public final Turret turret = new Turret();
public final VisionSystem visionSystem;
public final FlywheelSystem flywheel = new FlywheelSystem();
// TODO: consider whether other systems should be static, had to make this static for the dyanmic hood under trench.
public static final DriveSystem drivetrain = TunerConstants.createDrivetrain();

// public final HoodSystem hood = new HoodSystem();
public final Hood hood = new Hood();
public final Slapdown slapdown = new Slapdown();
// public final IntakePivotSystem intakePivot = new IntakePivotSystem();
// public final IntakeRollerSystem intakeRoller = new IntakeRollerSystem();
public final Intake intake = new Intake();
// public final HopperSystem hopper = new HopperSystem();
public final Hopper hopper = new Hopper();
public final UptakeSystem uptake = new UptakeSystem();
public final FlywheelSystem flywheel = new FlywheelSystem();
// TODO: consider whether other systems should be static, had to make this static for the dyanmic hood under trench.
public static final DriveSystem drivetrain = TunerConstants.createDrivetrain();
public final Uptake uptake = new Uptake();
public final Slapdown slapdown = new Slapdown();


private final SendableChooser<Command> autoChooser;

Expand All @@ -91,13 +90,15 @@ public RobotContainer() {
hood.setIO(new HoodIOTalonFX(hood));
slapdown.setIO(new SlapdownIOTalonFX(slapdown));
hopper.setIO(new HopperIOTalonFX(hopper));
uptake.setIO(new UptakeIOTalonFX(uptake));

visionSystem = new VisionSystem(drivetrain::getPose, Robot.m_field);
turret = new TurretSystem(visionSystem);
turret.setIO(new TurretIOTalonFX(turret), visionSystem);

NamedCommands.registerCommand("DeployIntake", slapdown.deployIntake());
NamedCommands.registerCommand("RunIntake", intake.runIntake());
NamedCommands.registerCommand("RunHopper", hopper.set(0.5));
NamedCommands.registerCommand("ShootBalls", uptake.setRoller(1));
NamedCommands.registerCommand("ShootBalls", uptake.set(1));
NamedCommands.registerCommand("Wiggle", slapdown.wiggleIntake());

configureBindings();
Expand Down Expand Up @@ -126,7 +127,7 @@ private void configureBindings() {
visionSystem.setDefaultCommand(visionSystem.setDefault(drivetrain, turret));

// Disable turret movement when no other turret commands are running.
turret.setDefaultCommand(turret.setDefault());
turret.setDefaultCommand(turret.getDefault());
flywheel.setDefaultCommand(flywheel.setDefault());
slapdown.setDefaultCommand(slapdown.getDefault());
intake.setDefaultCommand(intake.getDefault());
Expand Down Expand Up @@ -187,12 +188,12 @@ private void configureBindings() {
// Swaps the intake and shooting triggers if Maya mode is enabled, per Maya's preference.
if(ModifierConstants.MAYA_MODE) {
// Shooting on left trigger, intake on right trigger
driverController.leftTrigger().whileTrue(uptake.setRoller(1));
driverController.leftTrigger().whileTrue(uptake.set(1));
driverController.rightTrigger().whileTrue(intake.runIntake());
driverController.leftTrigger().whileTrue(hopper.set(1));
} else {
// Shooting on right trigger, intake on left trigger
driverController.rightTrigger().whileTrue(uptake.setRoller(1));
driverController.rightTrigger().whileTrue(uptake.set(1));
driverController.leftTrigger().whileTrue(intake.runIntake());
driverController.rightTrigger().whileTrue(hopper.set(1));
}
Expand Down Expand Up @@ -359,7 +360,7 @@ private Command toggleManualOverride() {
// at a low speed to clear any jams.
// TODO: remove from RobotContainer and into eventual Superstructure subsystem once it exists.
private Command forceOuttake() {
return uptake.setRoller(-0.5).alongWith(hopper.set(-0.5)).alongWith(intake.set(-0.5));
return uptake.set(-0.5).alongWith(hopper.set(-0.5)).alongWith(intake.set(-0.5));
}

/**
Expand Down
24 changes: 15 additions & 9 deletions src/main/java/org/team157/robot/subsystems/hopper/Hopper.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,27 +5,34 @@
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.SubsystemBase;

/**
* Represents the Hopper subsystem, which feeds balls
* from the intake into the uptake for shooting.
*/
public class Hopper extends SubsystemBase {
private HopperIO io;

// The IO interface for interacting with the hopper's motor.
private HopperIO io;

private final HopperIOInputsAutoLogged inputs = new HopperIOInputsAutoLogged();
// Inputs from the motor and mechanism, to be updated periodically and logged.
private final HopperIOInputsAutoLogged inputs = new HopperIOInputsAutoLogged();

/** Creates a new Hopper. */
public Hopper() {}
/**
* Specifies the IO implementation to be used for the hood.
/**
* Specifies the IO implementation to be used for the hopper.
*
* @param io An implementation of the Hood's IO layer, i.e. HoodIOTalonFX
* @param io An implementation of the Hopper's IO layer, i.e. HopperIOTalonFX
*/
public void setIO(HopperIO io) {
this.io = io;
}

/**
* Sets the default command of the hopper, stopping motor output when no other
* commands are running.
* Sets the default command of the hopper, stopping
* motor output when no other commands are running.
*
* @return Command setting the duty cycle output of the hood's motor to 0
* @return Command setting the duty cycle of the hopper's motor to 0
*/
public Command getDefault() {
return io.stop();
Expand Down Expand Up @@ -55,5 +62,4 @@ public void simulationPeriodic() {
io.simIterate();
}


}
Original file line number Diff line number Diff line change
Expand Up @@ -5,11 +5,15 @@
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;

/**
* Defines the input data to be logged by AdvantageKit, along with methods and
* {@link Command}s which an implementation of this IO interface must have.
*/
public interface HopperIO {

/**
* Represents the set of inputs which are to be logged by AdvantageKit
* and updated by an implementation of the {@link HoodIO} interface.
* and updated by an implementation of the {@link HopperIO} interface.
*/
@AutoLog
public static class HopperIOInputs {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,6 @@ public HopperIOTalonFX(SubsystemBase subsystem) {
SmartMotorControllerConfig hopperRollerMotorConfig = new SmartMotorControllerConfig(subsystem)
.withControlMode(ControlMode.OPEN_LOOP)
.withTelemetry("HopperRollerMotor", TelemetryConstants.TELEMETRY_VERBOSITY)
.withGearing(1)
.withMotorInverted(true)
.withIdleMode(MotorMode.COAST)
.withStatorCurrentLimit((HopperConstants.CURRENT_LIMIT))
Expand All @@ -50,7 +49,6 @@ public HopperIOTalonFX(SubsystemBase subsystem) {

this.hopper = new FlyWheel(hopperRollerConfig);
this.motor = hopper.getMotor();

}

@Override
Expand All @@ -70,15 +68,13 @@ public Command stop() {
}

@Override
public Command set(double dutycycle) {
return hopper.set(dutycycle);
public Command set(double dutyCycle) {
return hopper.set(dutyCycle);
}

@Override
public void simIterate() {
hopper.simIterate();
}



}

This file was deleted.

Loading
Loading