Skip to content

Commit

Permalink
Merge pull request #17 from frc937/intake
Browse files Browse the repository at this point in the history
Intake
  • Loading branch information
willitcode authored Jan 25, 2024
2 parents f8a5c12 + ed9cf41 commit f6b66a4
Show file tree
Hide file tree
Showing 4 changed files with 120 additions and 0 deletions.
12 changes: 12 additions & 0 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -40,4 +40,16 @@ public static class Drive {
/** The max speed the robot can rotate */
public static double MAX_ANGULAR_SPEED = Math.PI / 2;
}

public static class Intake {
/** Motor id of the Intake motor. */
public static final int INTAKE_MOTOR_ID = 0;

// It was me, DIO!
/** DIO Port ID for the Intake limit switch. */
public static final int INTAKE_LIMIT_SWITCH_DIO_PORT = 0;

/** Speed we want to run the Intake at. */
public static final double INTAKE_MOTOR_SPEED = 0.5;
}
}
6 changes: 6 additions & 0 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,9 @@
import frc.robot.commands.DriveFieldOriented;
import frc.robot.commands.DriveRobotOriented;
import frc.robot.commands.EnterXMode;
import frc.robot.commands.RunIntake;
import frc.robot.subsystems.Drive;
import frc.robot.subsystems.Intake;

/** Singleton class that contains all the robot's subsystems, commands, and button bindings. */
public class RobotContainer {
Expand All @@ -36,6 +38,8 @@ public class RobotContainer {
/** Singleton instance of {@link Drive} */
public static Drive drive = new Drive();

public static Intake intake = new Intake();

/*
* ************
* * COMMANDS *
Expand All @@ -46,6 +50,7 @@ public class RobotContainer {
private final DriveRobotOriented driveRobotOriented = new DriveRobotOriented();
private final DriveFieldOriented driveFieldOriented = new DriveFieldOriented();
private final EnterXMode enterXMode = new EnterXMode();
private final RunIntake runIntake = new RunIntake();

/*
* ***********************
Expand All @@ -71,6 +76,7 @@ private void configureBindings() {
driverController.leftStick().toggleOnTrue(driveFieldOriented);

driverController.x().onTrue(enterXMode);
driverController.a().onTrue(runIntake);
}

/**
Expand Down
49 changes: 49 additions & 0 deletions src/main/java/frc/robot/commands/RunIntake.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,49 @@
// 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.

/*
* Asimov's Laws:
* The First Law: A robot may not injure a human being or, through inaction, allow a human being to come to harm.
* The Second Law: A robot must obey the orders given it by human beings except where such orders would conflict with the First Law.
* The Third Law: A robot must protect its own existence as long as such protection does not conflict with the First or Second Law.
*/

package frc.robot.commands;

import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.RobotContainer;
import frc.robot.subsystems.Intake;

public class RunIntake extends Command {

private Intake intake;

/** Creates a new RunIntake. */
public RunIntake() {
this.intake = RobotContainer.intake;
addRequirements(intake);
}

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

// 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) {
intake.stop();
}

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

/*
* Asimov's Laws:
* The First Law: A robot may not injure a human being or, through inaction, allow a human being to come to harm.
* The Second Law: A robot must obey the orders given it by human beings except where such orders would conflict with the First Law.
* The Third Law: A robot must protect its own existence as long as such protection does not conflict with the First or Second Law.
*/

package frc.robot.subsystems;

import com.revrobotics.CANSparkLowLevel.MotorType;
import com.revrobotics.CANSparkMax;
import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants;

/** The intake of the robot. */
public class Intake extends SubsystemBase {

private CANSparkMax intake;
private DigitalInput limitSwitch;

/** Creates a new Intake. */
public Intake() {
this.intake = new CANSparkMax(Constants.Intake.INTAKE_MOTOR_ID, MotorType.kBrushless);
this.limitSwitch = new DigitalInput(Constants.Intake.INTAKE_LIMIT_SWITCH_DIO_PORT);
}

/** Runs the intake motors. */
public void runIntake() {
intake.set(Constants.Intake.INTAKE_MOTOR_SPEED);
}

/**
* Returns a boolean value on whether or not the Limit Switch (for the intake) has been activated.
*/
public boolean getLimitSwitch() {
return limitSwitch.get();
}

/** Stops the intake motors. */
public void stop() {
intake.set(0);
}

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

0 comments on commit f6b66a4

Please sign in to comment.