Skip to content

Commit

Permalink
created hopper subsystem and intake hopper🦟™️ (#8)
Browse files Browse the repository at this point in the history
* created hopper subsystem and intake hopper

* byebyebeyebveyebveyebeyebyebeyebbeyvbyeb

* fixed  my spelling error please dont crucify me🦟™️

* made it a constant🦟™️

* made it stop🦟™️

* fixed things based on comments🦟™️

* imported the motor ID to prevent conflicts🦟™️
  • Loading branch information
BrodyKarr authored Jan 11, 2025
1 parent 497768d commit 321494f
Show file tree
Hide file tree
Showing 5 changed files with 97 additions and 2 deletions.
7 changes: 7 additions & 0 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -250,4 +250,11 @@ public static class consClimber {
public static final double CLIMBER_MOTOR_VELOCITY = 0.5;

}

public static class constHopper {
public static final double HOPPER_SPEED = 0.5;

public static final TalonFXConfiguration HOPPER_CONFIG = new TalonFXConfiguration();

}
}
9 changes: 7 additions & 2 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -16,16 +16,20 @@
import frc.robot.RobotMap.mapControllers;
import frc.robot.commands.DriveManual;
import frc.robot.commands.ExampleAuto;
import frc.robot.subsystems.AlgaeIntake;
import frc.robot.commands.*;
import frc.robot.subsystems.CoralOuttake;
import frc.robot.subsystems.Drivetrain;
import frc.robot.subsystems.*;

public class RobotContainer {

private final SN_XboxController conDriver = new SN_XboxController(mapControllers.DRIVER_USB);
private final SN_XboxController conOperator = new SN_XboxController(mapControllers.OPERATOR_USB);

private final Drivetrain subDrivetrain = new Drivetrain();

private final Hopper subHopper = new Hopper();
private final IntakeHopper com_IntakeHopper = new IntakeHopper(subHopper);

private final AlgaeIntake subAlgaeIntake = new AlgaeIntake();
private final CoralOuttake subCoralOuttake = new CoralOuttake();

Expand All @@ -51,6 +55,7 @@ private void configureDriverBindings(SN_XboxController controller) {
controller.btn_LeftBumper
.whileTrue(Commands.runOnce(() -> subDrivetrain.setRobotRelative()))
.onFalse(Commands.runOnce(() -> subDrivetrain.setFieldRelative()));
conDriver.btn_Back.whileTrue(com_IntakeHopper);
}

private void configureOperatorBindings(SN_XboxController controller) {
Expand Down
5 changes: 5 additions & 0 deletions src/main/java/frc/robot/RobotMap.java
Original file line number Diff line number Diff line change
Expand Up @@ -46,4 +46,9 @@ public static class mapAlgaeIntake {
public static class mapCoralOuttake {
public static final int CORAL_OUTTAKE_MOTOR_CAN = 30;
}

// Hopper is 40-49
public static class mapHopper {
public static final int HOPPER_MOTOR_CAN = 40;
}
}
45 changes: 45 additions & 0 deletions src/main/java/frc/robot/commands/IntakeHopper.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,45 @@
// 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 edu.wpi.first.wpilibj2.command.Command;
import frc.robot.Constants.constHopper;
import frc.robot.subsystems.Hopper;

/* You should consider using the more terse Command factories API instead https://docs.wpilib.org/en/stable/docs/software/commandbased/organizing-command-based.html#defining-commands */
public class IntakeHopper extends Command {

Hopper subHopper;

/** Creates a new Intake_Hopper. */
public IntakeHopper(Hopper subHopper) {
// Use addRequirements() here to declare subsystem dependencies.
this.subHopper = subHopper;
}

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

subHopper.runHopper(constHopper.HOPPER_SPEED);
}

// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
}

// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
subHopper.runHopper(0);
}

// Returns true when the command should end.
@Override
public boolean isFinished() {
return false;
}
}
33 changes: 33 additions & 0 deletions src/main/java/frc/robot/subsystems/Hopper.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
// 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.subsystems;

import com.ctre.phoenix6.hardware.TalonFX;

import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants.constHopper;
import frc.robot.RobotMap.mapHopper;

public class Hopper extends SubsystemBase {

TalonFX hopperMotor;

/** Creates a new hopper. */
public Hopper() {
hopperMotor = new TalonFX(mapHopper.HOPPER_MOTOR_CAN);

hopperMotor.getConfigurator().apply(constHopper.HOPPER_CONFIG);

}

public void runHopper(double speed) {
hopperMotor.set(speed);
}

@Override
public void periodic() {
// This method will be called once per scheduler run
}
}

0 comments on commit 321494f

Please sign in to comment.