Skip to content

Commit

Permalink
make intake without beam-break sensors
Browse files Browse the repository at this point in the history
  • Loading branch information
team6101 committed Feb 26, 2024
1 parent c5f020a commit 1263519
Show file tree
Hide file tree
Showing 5 changed files with 23 additions and 5 deletions.
1 change: 1 addition & 0 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@ public class Constants {
public static final int DRIVE_LEFT_CHILD_ID = 8;
public static final int DRIVE_RIGHT_PARENT_ID = 11;
public static final int DRIVE_RIGHT_CHILD_ID = 3;
public static final int INTAKE_ID = 6101;

/*CLIMB MOTOR IDS */

Expand Down
8 changes: 8 additions & 0 deletions src/main/java/frc/robot/InputtedCoDriverControls.java
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,9 @@ public static void onEveryFrame() {
shootIntoSpeaker();
}
doShooterIntake();
if (controller.getYButton()) {
doFloorIntake();
}
if (controller.getStartButton()) {
extendArms();
}
Expand All @@ -31,6 +34,11 @@ public static void onEveryFrame() {
}
}

private static void doFloorIntake() {
Robot.motors.getIntake().set(.5);
//Robot.motors.getFeeder().set(.5);
}

private static void extendArms() {
Robot.getTeleopActionRunner().addActionToRun(new ExtendArms());
}
Expand Down
9 changes: 6 additions & 3 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
package frc.robot;

import com.kauailabs.navx.frc.AHRS;
import com.revrobotics.CANSparkLowLevel.MotorType;
import edu.wpi.first.wpilibj.GenericHID.RumbleType;
import edu.wpi.first.wpilibj.SPI;
import edu.wpi.first.wpilibj.TimedRobot;
Expand Down Expand Up @@ -44,6 +45,7 @@ public class Robot extends TimedRobot {
MotorController feederMotor = MotorControllerFactory.create(9, MotorController.Type.SparkMax);
MotorController leftClimb = MotorControllerFactory.create(Constants.LEFT_CLIMB_ID, MotorController.Type.Talon);
MotorController rightClimb = MotorControllerFactory.create(Constants.RIGHT_CLIMB_ID, MotorController.Type.Talon);
MotorController intake = MotorControllerFactory.create(Constants.INTAKE_ID, MotorController.Type.SparkMax);
XboxController driverController = new XboxController(Constants.DRIVER_CONTROLLER_ID);
XboxController coDriverController = new XboxController(1);
static AHRS navX = new AHRS(SPI.Port.kMXP);
Expand Down Expand Up @@ -82,7 +84,7 @@ public void robotInit() {

feederMotor.setInverted(true);

System.out.println("is drive righjt parent inverted? " + driveRightParent.getInverted());
System.out.println("is drive right parent inverted? " + driveRightParent.getInverted());

driveLeftChild.setBrakeMode(false);
driveLeftParent.setBrakeMode(false);
Expand All @@ -99,7 +101,8 @@ public void robotInit() {
.leftFlywheel(leftFlywheel)
.rightFlywheel(rightFlywheel)
.leftClimb(leftClimb)
.rightClimb(rightClimb);
.rightClimb(rightClimb)
.intake(intake);
getGyroscope().reset();
System.out.println(Constants.APRIL_TAG_CONFIDENCE_FRAMES);
SmartDashboard.putNumber("rotationGainsP", Constants.ROTATION_GAINS.P);
Expand All @@ -108,7 +111,7 @@ public void robotInit() {

SmartDashboard.putNumber("PIDTARGET", 90);

System.out.println("is drive righjt parent inverted at end?? " + driveRightParent.getInverted());
System.out.println("is drive right parent inverted at end?? " + driveRightParent.getInverted());

InputtedCoDriverControls.setCoDriverController(coDriverController);
}
Expand Down
9 changes: 7 additions & 2 deletions src/main/java/frc/robot/RobotMotors.java
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,11 @@ public class RobotMotors {
MotorController rightFlywheel;
MotorController leftClimb;
MotorController rightClimb;
MotorController intake;

public MotorController getIntake() {
return intake;
}

public MotorController getDriveLeftParent() {
return driveLeftParent;
Expand Down Expand Up @@ -87,8 +92,8 @@ public RobotMotors rightFlywheel(MotorController rightFlywheel) {
return this;
}

public RobotMotors intakeMotor(MotorController intakeMotor) {
this.feeder = intakeMotor;
public RobotMotors intake(MotorController intake) {
this.intake = intake;
return this;
}

Expand Down
1 change: 1 addition & 0 deletions src/main/java/frc/robot/auton/AutonShoot.java
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@ public class AutonShoot extends AutonAction {
public boolean isDone() {
if (Timer.getFPGATimestamp() >= revFinishedTime) {
Robot.motors.getFeeder().set(0.2);
Robot.motors.getIntake().set(.2);
}
if (Timer.getFPGATimestamp() >= revFinishedTime + 1.0) {
Robot.motors.getFeeder().set(0);
Expand Down

0 comments on commit 1263519

Please sign in to comment.