Skip to content
Draft
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
17 changes: 9 additions & 8 deletions src/main/java/frc/robot/Orchestrator.java
Original file line number Diff line number Diff line change
Expand Up @@ -8,11 +8,11 @@
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Transform2d;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import frc.lib.utils.AllianceFlipUtil;
import frc.lib.utils.TunableNumber;
import frc.robot.FieldConstants.Hub;
import frc.robot.commands.auto.DriveToPose;
import frc.robot.commands.auto.RotateToOrientation;
Expand All @@ -28,6 +28,9 @@
import org.littletonrobotics.junction.Logger;

public class Orchestrator {
private static final TunableNumber testRadPerSec =
new TunableNumber("Shooter/TestRadPerSec", CLOSE_HUB_SHOOTER_RPM);

private final double FRONT_HUB_OFFSET = Units.inchesToMeters(40.0);
private final Drive drive;
private final Shooter shooter;
Expand Down Expand Up @@ -158,13 +161,11 @@ public Command feedUp() {
}

public Command spinUpShooterTest() {
SmartDashboard.putNumber("Shooter/TestRPM", CLOSE_HUB_SHOOTER_RPM);
return shooter
.setTargetVelocityRadians(
() ->
Units.rotationsPerMinuteToRadiansPerSecond(
SmartDashboard.getNumber("Shooter/TestRPM", 1000.0)))
.withName("spinUpShooterTest");
<<<<<<< HEAD
return shooter.setTargetVelocityRadians(() -> testRPM.get()).withName("spinUpShooterTest");
=======
return shooter.setTargetVelocityRadians(testRadPerSec).withName("spinUpShooterTest");
>>>>>>> refs/remotes/origin/regression
}

public Command spinUpShooterDistance(DoubleSupplier targetDistance) {
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -308,8 +308,8 @@ public RobotContainer() {

autoChooser.addOption("pp", autos.ppACycleLeft());
autoChooser.addOption("ppB", autos.ppBCycleRight());
autoChooser.addOption("ppB Cycle Right Regression", autos.ppBCycleRightRegression());
autoChooser.addOption("ppA Cycle Left Regression", autos.ppACycleLeftRegression());
// autoChooser.addOption("ppB Cycle Right Regression", autos.ppBCycleRightRegression());
// autoChooser.addOption("ppA Cycle Left Regression", autos.ppACycleLeftRegression());
// Configure the button bindings
configureButtonBindings();
}
Expand Down
40 changes: 0 additions & 40 deletions src/main/java/frc/robot/commands/auto/Autos.java
Original file line number Diff line number Diff line change
Expand Up @@ -149,46 +149,6 @@ public Command ppBCycleRight() {
orchestrator.feedUp()));
}

public Command ppBCycleRightRegression() {
return Commands.sequence(
Commands.runOnce(() -> drive.setPose(startBside.get())),
Commands.deadline(
drive.getAutonomousCommand("B-Cycle-RightSweep"),
intake.extendToAngleAndIntake(IntakeConstants.EXTEND_POS).withTimeout(5.5))
.withTimeout(14.5),
Commands.deadline(
orchestrator.aimToHub().withTimeout(2.5),
orchestrator.spinUpShooterDistance(orchestrator.getHubDistance())),
Commands.parallel(
orchestrator.spinUpShooterDistance(orchestrator.getHubDistance()),
orchestrator.feedUp())
.withTimeout(2.5),
Commands.parallel(
intake.extendToAngleAndIntake(IntakeConstants.COLLAPSE_POS),
orchestrator.spinUpShooterDistance(orchestrator.getHubDistance()),
orchestrator.feedUp()));
}

public Command ppACycleLeftRegression() {
return Commands.sequence(
Commands.runOnce(() -> drive.setPose(startAside.get())),
Commands.deadline(
drive.getAutonomousCommand("A-Cycle-LeftSweep"),
intake.extendToAngleAndIntake(IntakeConstants.EXTEND_POS).withTimeout(5.5))
.withTimeout(14.5),
Commands.deadline(
orchestrator.aimToHub().withTimeout(2.5),
orchestrator.spinUpShooterDistance(orchestrator.getHubDistance())),
Commands.parallel(
orchestrator.spinUpShooterDistance(orchestrator.getHubDistance()),
orchestrator.feedUp())
.withTimeout(2.5),
Commands.parallel(
intake.extendToAngleAndIntake(IntakeConstants.COLLAPSE_POS),
orchestrator.spinUpShooterDistance(orchestrator.getHubDistance()),
orchestrator.feedUp()));
}

public Command EightBalls() {
return Commands.sequence(
Commands.deadline(
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/subsystems/shooter/Shooter.java
Original file line number Diff line number Diff line change
Expand Up @@ -174,7 +174,7 @@ public double getAirTimeSeconds(DoubleSupplier distance) {
public DoubleSupplier calculateSetpoint(DoubleSupplier distance) {
// calculate rad/s depending on distance
return () -> {
double setpoint = 183.35 * distance.getAsDouble() + 750.93;
double setpoint = 223 * distance.getAsDouble() + 750.93;
if (setpoint > 5000) {
return 5000;
} else return setpoint;
Expand Down
Loading