Skip to content

Commit

Permalink
shooter changes
Browse files Browse the repository at this point in the history
  • Loading branch information
Nins97 committed Feb 21, 2024
1 parent 8c975b3 commit 169b6f7
Show file tree
Hide file tree
Showing 5 changed files with 22 additions and 16 deletions.
10 changes: 5 additions & 5 deletions src/main/java/frc/robot/BuildConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,12 +7,12 @@ public final class BuildConstants {
public static final String MAVEN_GROUP = "";
public static final String MAVEN_NAME = "Competition2024";
public static final String VERSION = "unspecified";
public static final int GIT_REVISION = 114;
public static final String GIT_SHA = "1777ba50499098176f582e0eae64cdea9e35c8ab";
public static final String GIT_DATE = "2024-02-20 16:34:07 MST";
public static final int GIT_REVISION = 115;
public static final String GIT_SHA = "8c975b34b659b8bf7369f379e803422cd3dae397";
public static final String GIT_DATE = "2024-02-21 08:03:57 MST";
public static final String GIT_BRANCH = "workingongettingready";
public static final String BUILD_DATE = "2024-02-20 19:36:55 MST";
public static final long BUILD_UNIX_TIME = 1708483015286L;
public static final String BUILD_DATE = "2024-02-21 09:21:03 MST";
public static final long BUILD_UNIX_TIME = 1708532463510L;
public static final int DIRTY = 1;

private BuildConstants(){}
Expand Down
8 changes: 4 additions & 4 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -181,10 +181,7 @@ private void configureOperatorBindings() {
// operatorController
// .rightStick()
// .whileTrue(elevatorSubsystem.runElevatorCommand(operatorController.getRightY()));
operatorController
.rightTrigger()
.onTrue(
new ShootAtAngleCommand(
operatorController.rightTrigger().onTrue(new ShootAtAngleCommand(
shooterSubsystem, transportSubsystem, wristSubsystem, SHOOTING_ANGLE));
operatorController
.leftTrigger()
Expand All @@ -200,6 +197,9 @@ private void configureOperatorBindings() {
.onTrue(
new AmpPlaceCommand(
elevatorSubsystem, wristSubsystem, shooterSubsystem, transportSubsystem));
operatorController.share().whileTrue(Commands.parallel(elevatorSubsystem.setElevatorPositionCommand(0), slapdownSubsystem.setFeederVoltageCommand(6), intakeSubsystem.setIntakeVoltageCommand(6), transportSubsystem.setVoltageCommand(6.0).until(transportSubsystem::atSensor).andThen(transportSubsystem.setVoltageCommand(0.0))));
// operatorController.share().onTrue(transportSubsystem.setVoltageCommand(6.0).until(transportSubsystem::atSensor));
operatorController.options().whileTrue(Commands.parallel(elevatorSubsystem.setElevatorPositionCommand(Units.inchesToMeters(3)), shooterSubsystem.runVelocityCommand(3000.0/60), Commands.sequence(Commands.waitUntil(() -> shooterSubsystem.getVelocity() >= Units.rotationsToRadians(3000.0/60)), transportSubsystem.setVoltageCommand(10.0))));
}

private void configureDriving() {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -118,7 +118,7 @@ private void configMotors() {
}

public void atBottomLimit() {
if (bottomLimit.get()) {
if (!bottomLimit.get()) {
elevatorEncoder.setPosition(0);
}
}
Expand Down Expand Up @@ -175,15 +175,15 @@ public Command sysIdDynamic(SysIdRoutine.Direction direction) {
@Override
public void periodic() {
// TODO: make this or elegant
if (bottomLimit.get()) {
if (!bottomLimit.get()) {
elevatorEncoder.setPosition(0.0);
}
logValues();
}

private void logValues() {
elevatorMotor.logValues();
bottomLimitEntry.append(bottomLimit.get());
bottomLimitEntry.append(!bottomLimit.get());

if (FF_GAINS.hasChanged()) {
feedforward = FF_GAINS.createElevatorFeedforward();
Expand Down
12 changes: 9 additions & 3 deletions src/main/java/frc/robot/subsystems/shooter/ShooterSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
import com.revrobotics.CANSparkMax;
import com.revrobotics.RelativeEncoder;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine;
Expand Down Expand Up @@ -43,7 +44,7 @@ public class ShooterSubsystem extends SubsystemBase {
private final SimpleMotorFeedforward feedforward = SHOOTER_FF_GAINS.createFeedforward();

private final DoubleTelemetryEntry flyVoltageReq =
new DoubleTelemetryEntry("/shooter/voltageReq", false);
new DoubleTelemetryEntry("/shooter/voltageReq", true);
private final EventTelemetryEntry shooterEventEntry = new EventTelemetryEntry("/shooter/events");

public ShooterSubsystem() {
Expand Down Expand Up @@ -115,16 +116,21 @@ public void setVoltage(double voltage) {
flywheelMotor.setVoltage(voltage);
}

public double getVelocity() {
return flywheelEncoder.getVelocity();
}

public Command setVoltageCommand(double voltage) {
return this.run(() -> setVoltage(voltage));
}

public Command runVelocityCommand(double setpointRotationsPerSecond) {
double radiansPerSecond = Units.rotationsToRadians(setpointRotationsPerSecond);
return this.run(
() ->
setVoltage(
pidController.calculate(flywheelEncoder.getVelocity(), setpointRotationsPerSecond)
+ feedforward.calculate(setpointRotationsPerSecond)));
pidController.calculate(flywheelEncoder.getVelocity(), radiansPerSecond)
+ feedforward.calculate(radiansPerSecond)));
}

public Command sysIdQuasistatic(SysIdRoutine.Direction direction) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -86,7 +86,7 @@ public void configMotor() {
}

public boolean atSensor() {
return shooterSensor.get();
return !shooterSensor.get();
}

public Command runTransportOutCommand() {
Expand Down

0 comments on commit 169b6f7

Please sign in to comment.