Skip to content

Commit

Permalink
added driver commands: note intake, note outtake, note shoot; added c…
Browse files Browse the repository at this point in the history
…ommand SetFeedersTargetRPM
  • Loading branch information
CSnair7 committed Feb 27, 2024
1 parent 71150ca commit 6131a9c
Show file tree
Hide file tree
Showing 4 changed files with 78 additions and 2 deletions.
2 changes: 1 addition & 1 deletion build.gradle
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
plugins {
id "java"
id "edu.wpi.first.GradleRIO" version "2024.2.1"
id "edu.wpi.first.GradleRIO" version "2024.3.1"
id "com.peterabeles.gversion" version "1.10"
id "com.diffplug.spotless" version "6.12.0"
}
Expand Down
6 changes: 6 additions & 0 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -67,12 +67,16 @@ public static class ModuleConstants {
public static class IntakeConstants {
public static final int CURRENT_LIMIT = 30;
public static final boolean CURRENT_LIMIT_ENABLED = true;

public static final double INTAKE_NOTE_VELOCITY_RPM = -100;
}

public static final class ShooterConstants {
public static final double FEEDER_CURRENT_LIMIT = 40;
public static final boolean FEEDER_CURRENT_LIMIT_ENABLED = true;

public static final double FEEDER_INTAKE_NOTE_VELOCITY_RPM = -100;

public static final double FLYWHEEL_CURRENT_LIMIT = 40;
public static final boolean FLYWHEEL_CURRENT_LIMIT_ENABLED = true;

Expand Down Expand Up @@ -103,6 +107,8 @@ public static class PivotConstants {
public static final double[] PID = {0, 0, 0};

public static final double REDUCTION = (15.0 / 1.0) * (34.0 / 24.0) * (24.0 / 18.0) * (50.0/14.0);

public static final double PIVOT_ANGLE_DEGREES = 30;
}

public static class LEDConstants {
Expand Down
28 changes: 27 additions & 1 deletion src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -21,8 +21,11 @@
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.ParallelCommandGroup;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import frc.robot.commands.DriveCommands;
import frc.robot.commands.SetFeedersTargetRPM;
import frc.robot.commands.SetPivotTarget;
import frc.robot.subsystems.drive.Drive;
import frc.robot.subsystems.drive.GyroIO;
import frc.robot.subsystems.drive.GyroIOPigeon2;
Expand Down Expand Up @@ -173,8 +176,10 @@ private void configureButtonBindings() {
() -> -controller.getLeftX(),
() -> -controller.getRightX()));
// controller.x().onTrue(Commands.runOnce(drive::stopWithX, drive));

// resets the gyro
controller
.b()
.start()
.onTrue(
Commands.runOnce(
() ->
Expand All @@ -192,6 +197,27 @@ private void configureButtonBindings() {
controller.a().onTrue(new InstantCommand(() -> intake.setRollerVelocityRPM(1000), intake));
controller.a().onFalse(new InstantCommand(intake::stopRollers, intake));

// note intake
controller.rightBumper().whileTrue(new ParallelCommandGroup(
new SetPivotTarget(Constants.PivotConstants.PIVOT_ANGLE_DEGREES, pivot),

new InstantCommand(() -> intake.setRollerVelocityRPM(Constants.IntakeConstants.INTAKE_NOTE_VELOCITY_RPM)),

new SetFeedersTargetRPM(Constants.ShooterConstants.FEEDER_INTAKE_NOTE_VELOCITY_RPM, shooter)
));

// note outtake
controller.leftBumper().whileTrue(new ParallelCommandGroup(
new SetPivotTarget(Constants.PivotConstants.PIVOT_ANGLE_DEGREES, pivot),

new InstantCommand(() -> intake.setRollerVelocityRPM(-1 * Constants.IntakeConstants.INTAKE_NOTE_VELOCITY_RPM)),

new SetFeedersTargetRPM(-1 * Constants.ShooterConstants.FEEDER_INTAKE_NOTE_VELOCITY_RPM, shooter)
));

// note shoot
controller.rightTrigger().whileTrue(new SetFeedersTargetRPM(Constants.ShooterConstants.FEEDER_INTAKE_NOTE_VELOCITY_RPM, shooter));

// controller.a().onTrue(new SetElevatorTarget(10, elevator));
// controller.a().onFalse(new InstantCommand(elevator::elevatorStop, elevator));

Expand Down
44 changes: 44 additions & 0 deletions src/main/java/frc/robot/commands/SetFeedersTargetRPM.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,44 @@
// 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.subsystems.shooter.Shooter;

public class SetFeedersTargetRPM extends Command {
/** Creates a new SetFeedersRPM. */

private final Shooter shooter;
private final double rpm;

public SetFeedersTargetRPM(double rpm, Shooter shooter) {
this.rpm = rpm;
this.shooter = shooter;

addRequirements(shooter);
// Use addRequirements() here to declare subsystem dependencies.
}

// Called when the command is initially scheduled.
@Override
public void initialize() {
shooter.setFeedersRPM(rpm);
}

// 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) {}

// Returns true when the command should end.
// TODO needs to be implemented
@Override
public boolean isFinished() {
return false;
}
}

0 comments on commit 6131a9c

Please sign in to comment.