diff --git a/src/main/java/frc4388/robot/Constants.java b/src/main/java/frc4388/robot/Constants.java index 3a18d3a..466ff74 100644 --- a/src/main/java/frc4388/robot/Constants.java +++ b/src/main/java/frc4388/robot/Constants.java @@ -33,6 +33,10 @@ public final class Constants { public static final double ENCODER_TICKS_PER_REV = 2048; } + + public static final class IntakeConstants { + public static final int INTAKE_SPARK_ID = 1; + } public static final class LEDConstants { public static final int LED_SPARK_ID = 0; diff --git a/src/main/java/frc4388/robot/RobotContainer.java b/src/main/java/frc4388/robot/RobotContainer.java index 6469cc8..fac6bd7 100644 --- a/src/main/java/frc4388/robot/RobotContainer.java +++ b/src/main/java/frc4388/robot/RobotContainer.java @@ -17,7 +17,9 @@ import edu.wpi.first.wpilibj2.command.button.JoystickButton; import frc4388.robot.Constants.*; import frc4388.robot.commands.DriveToDistanceMM; import frc4388.robot.commands.DriveToDistancePID; +import frc4388.robot.commands.RunIntakeWithTriggers; import frc4388.robot.subsystems.Drive; +import frc4388.robot.subsystems.Intake; import frc4388.robot.subsystems.LED; import frc4388.utility.LEDPatterns; import frc4388.utility.controller.IHandController; @@ -34,6 +36,7 @@ public class RobotContainer { /* Subsystems */ private final Drive m_robotDrive = new Drive(); private final LED m_robotLED = new LED(); + private final Intake m_robotIntake = new Intake(); /* Controllers */ private final XboxController m_driverXbox = new XboxController(OIConstants.XBOX_DRIVER_ID); @@ -50,6 +53,8 @@ public class RobotContainer { m_robotDrive.setDefaultCommand(new RunCommand(() -> m_robotDrive.driveWithInput( getDriverController().getLeftYAxis(), getDriverController().getRightXAxis()), m_robotDrive)); + // drives motor with input from triggers on the opperator controller + m_robotIntake.setDefaultCommand(new RunIntakeWithTriggers(m_robotIntake, getOperatorController())); // continually sends updates to the Blinkin LED controller to keep the lights on m_robotLED.setDefaultCommand(new RunCommand(() -> m_robotLED.updateLED(), m_robotLED)); } diff --git a/src/main/java/frc4388/robot/commands/RunIntakeWithTriggers.java b/src/main/java/frc4388/robot/commands/RunIntakeWithTriggers.java new file mode 100644 index 0000000..359ea0e --- /dev/null +++ b/src/main/java/frc4388/robot/commands/RunIntakeWithTriggers.java @@ -0,0 +1,64 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) 2019 FIRST. All Rights Reserved. */ +/* Open Source Software - may be modified and shared by FRC teams. The code */ +/* must be accompanied by the FIRST BSD license file in the root directory of */ +/* the project. */ +/*----------------------------------------------------------------------------*/ + +package frc4388.robot.commands; + +import edu.wpi.first.wpilibj2.command.CommandBase; +import frc4388.robot.subsystems.Intake; +import frc4388.utility.controller.IHandController; + +public class RunIntakeWithTriggers extends CommandBase { + private Intake m_intake; + private IHandController m_controller; + + /** + * Uses input from opperator triggers to control intake motor + * @param subsystem the intake subsystem + * @param controller the operator controller + */ + public RunIntakeWithTriggers(Intake subsystem, IHandController controller) { + // Use addRequirements() here to declare subsystem dependencies. + m_intake = subsystem; + m_controller = controller; + addRequirements(m_intake); + } + + // 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 rightTrigger = m_controller.getRightTriggerAxis(); + double leftTrigger = m_controller.getLeftTriggerAxis(); + double output = 0; + if (rightTrigger < .5) { + if(rightTrigger > leftTrigger) { + output = rightTrigger; + } + if (leftTrigger > rightTrigger) { + output = leftTrigger; + } + } else { + output = rightTrigger; + } + m_intake.runIntake(output); + } + + // Called once the command ends or is interrupted. + @Override + public void end(boolean interrupted) { + } + + // Returns true when the command should end. + @Override + public boolean isFinished() { + return false; + } +} diff --git a/src/main/java/frc4388/robot/subsystems/Intake.java b/src/main/java/frc4388/robot/subsystems/Intake.java new file mode 100644 index 0000000..f718cb6 --- /dev/null +++ b/src/main/java/frc4388/robot/subsystems/Intake.java @@ -0,0 +1,36 @@ +/*----------------------------------------------------------------------------*/ +/* Copyright (c) 2019 FIRST. All Rights Reserved. */ +/* Open Source Software - may be modified and shared by FRC teams. The code */ +/* must be accompanied by the FIRST BSD license file in the root directory of */ +/* the project. */ +/*----------------------------------------------------------------------------*/ + +package frc4388.robot.subsystems; + +import edu.wpi.first.wpilibj.Spark; +import edu.wpi.first.wpilibj2.command.SubsystemBase; +import frc4388.robot.Constants.IntakeConstants; + +public class Intake extends SubsystemBase { + Spark m_intakeMotor = new Spark(IntakeConstants.INTAKE_SPARK_ID); + + /** + * Creates a new Intake. + */ + public Intake() { + m_intakeMotor.setInverted(false); + } + + @Override + public void periodic() { + // This method will be called once per scheduler run + } + + /** + * Runs intake motor + * @param input the voltage to run motor at + */ + public void runIntake(double input) { + m_intakeMotor.set(input); + } +}