Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Source Intake #42

Merged
merged 7 commits into from
Apr 18, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 3 additions & 2 deletions Robot2024/src/main/java/com/team2813/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -40,16 +40,17 @@ public static class OperatorConstants {

//square = cross, cross = circle, circle = square

public static final Trigger climbUpButton = operatorController.povUp();
public static final Trigger climbUpButton = operatorController.povUp().and(() -> false);
public static final Trigger climbDownButton = operatorController.povDown();
public static final Trigger altOuttakeButton = new Trigger(() -> operatorXboxController.getLeftTriggerAxis() >= 0.5).and(() -> false);
public static final Trigger sourceIntake = operatorController.povUp();

}
public static class DriverConstants {
public static final int driverControllerPort = 0;
public static final CommandPS4Controller DRIVER_CONTROLLER = new CommandPS4Controller(driverControllerPort);
public static final Trigger slowmodeButton = DRIVER_CONTROLLER.L1();
public static final Trigger orientButton = DRIVER_CONTROLLER.R2();
public static final Trigger orientButton = DRIVER_CONTROLLER.R2(); // options
public static final Trigger spoolAutoAimButton = DRIVER_CONTROLLER.square(); // actually maps to cross
public static final Trigger ampIntakeButton = DRIVER_CONTROLLER.triangle(); //R2
public static final Trigger autoAimButton = DRIVER_CONTROLLER.R1();
Expand Down
28 changes: 28 additions & 0 deletions Robot2024/src/main/java/com/team2813/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@
import static com.team2813.Constants.OperatorConstants.shootPodium;
import static com.team2813.Constants.OperatorConstants.shootWooferFront;
import static com.team2813.Constants.OperatorConstants.shootWooferSide;
import static com.team2813.Constants.OperatorConstants.sourceIntake;

import com.pathplanner.lib.auto.AutoBuilder;
import com.pathplanner.lib.auto.NamedCommands;
Expand All @@ -44,6 +45,7 @@
import com.team2813.subsystems.Magazine;
import com.team2813.subsystems.Shooter;
import com.team2813.subsystems.ShooterPivot;
import com.team2813.subsystems.ShooterPivot.Position;

import edu.wpi.first.net.PortForwarder;
import edu.wpi.first.wpilibj.XboxController;
Expand Down Expand Up @@ -206,6 +208,32 @@ private void configureBindings(AutoCommands autoCommands) {
shootPodium.onTrue(autoCommands.shootPodium());
farSpeaker.onTrue(autoCommands.farSpeaker());
autoAimButton.onTrue(new AutoAimCommand(shooter, shooterPivot, mag, drive));

sourceIntake.onTrue(
new SequentialCommandGroup(
new LockFunctionCommand(shooterPivot::atPosition, () -> shooterPivot.setSetpoint(Position.SOURCE_INTAKE), shooterPivot),
new InstantCommand(shooter::reverse, shooter)
)
);
sourceIntake.onFalse(
new SequentialCommandGroup(
new ParallelCommandGroup(
new InstantCommand(mag::reverseMag, mag),
new InstantCommand(intake::outtakeNote, intake)
),
new WaitCommand(0.1),
new ParallelCommandGroup(
new InstantCommand(shooter::stop, shooter),
new InstantCommand(intake::intake, intake),
new InstantCommand(mag::runOnlyMag, mag)
),
new WaitCommand(0.1),
new ParallelCommandGroup(
new InstantCommand(intake::stopIntakeMotor, intake),
new InstantCommand(mag::stop, mag)
)
)
);
}

public Command getAutonomousCommand() {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ public void execute() {
double val = control.getAsDouble();
if (Math.abs(val) > DEADZONE) {
shooterPivot.set(ControlMode.DUTY_CYCLE, val * MULTIPLIER);
} else {
} else if (!shooterPivot.isEnabled()) {
shooterPivot.set(ControlMode.DUTY_CYCLE, 0);
}
}
Expand Down
7 changes: 0 additions & 7 deletions Robot2024/src/main/java/com/team2813/subsystems/Drive.java
Original file line number Diff line number Diff line change
Expand Up @@ -163,13 +163,6 @@ public Drive() {
Shuffleboard.getTab("swerve").add("rotation PID", facingRequest.HeadingController);
}

private void setLimits(int module) {
drivetrain.getModule(0).getDriveMotor()
.getConfigurator().apply(new CurrentLimitsConfigs()
.withSupplyCurrentLimit(40)
.withSupplyCurrentLimitEnable(true));
}

final SwerveRequest.FieldCentricFacingAngle facingRequest;

public void turnToFace(Rotation2d rotation) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -48,5 +48,6 @@ public void runOnlyMag() {

public void reverseMag() {
magMotor.set(ControlMode.DUTY_CYCLE, -0.6);
kickerMotor.set(ControlMode.DUTY_CYCLE, -0.6);
}
}
5 changes: 5 additions & 0 deletions Robot2024/src/main/java/com/team2813/subsystems/Shooter.java
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,11 @@ public boolean atVelocity() {
return shooterMotor.getVelocity() - targetVelocity > -1;
}

public void reverse() {
targetVelocity = 0;
shooterMotor.set(ControlMode.DUTY_CYCLE, -0.2);
}

public void stop() {
targetVelocity = 0;
shooterMotor.set(ControlMode.VELOCITY, 0);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -70,6 +70,7 @@ public static enum Position implements MotorSubsystem.Position {
PODIUM(0.076660),
TEST(0.067871),
FAR_SPEAKER(0.088135),
SOURCE_INTAKE(0.048096),
BOTTOM_HARD_STOP(0.099854);

private final double pos;
Expand Down
Loading