Skip to content

Commit 169b6f7

Browse files
committed
shooter changes
1 parent 8c975b3 commit 169b6f7

File tree

5 files changed

+22
-16
lines changed

5 files changed

+22
-16
lines changed

src/main/java/frc/robot/BuildConstants.java

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -7,12 +7,12 @@ public final class BuildConstants {
77
public static final String MAVEN_GROUP = "";
88
public static final String MAVEN_NAME = "Competition2024";
99
public static final String VERSION = "unspecified";
10-
public static final int GIT_REVISION = 114;
11-
public static final String GIT_SHA = "1777ba50499098176f582e0eae64cdea9e35c8ab";
12-
public static final String GIT_DATE = "2024-02-20 16:34:07 MST";
10+
public static final int GIT_REVISION = 115;
11+
public static final String GIT_SHA = "8c975b34b659b8bf7369f379e803422cd3dae397";
12+
public static final String GIT_DATE = "2024-02-21 08:03:57 MST";
1313
public static final String GIT_BRANCH = "workingongettingready";
14-
public static final String BUILD_DATE = "2024-02-20 19:36:55 MST";
15-
public static final long BUILD_UNIX_TIME = 1708483015286L;
14+
public static final String BUILD_DATE = "2024-02-21 09:21:03 MST";
15+
public static final long BUILD_UNIX_TIME = 1708532463510L;
1616
public static final int DIRTY = 1;
1717

1818
private BuildConstants(){}

src/main/java/frc/robot/RobotContainer.java

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -181,10 +181,7 @@ private void configureOperatorBindings() {
181181
// operatorController
182182
// .rightStick()
183183
// .whileTrue(elevatorSubsystem.runElevatorCommand(operatorController.getRightY()));
184-
operatorController
185-
.rightTrigger()
186-
.onTrue(
187-
new ShootAtAngleCommand(
184+
operatorController.rightTrigger().onTrue(new ShootAtAngleCommand(
188185
shooterSubsystem, transportSubsystem, wristSubsystem, SHOOTING_ANGLE));
189186
operatorController
190187
.leftTrigger()
@@ -200,6 +197,9 @@ private void configureOperatorBindings() {
200197
.onTrue(
201198
new AmpPlaceCommand(
202199
elevatorSubsystem, wristSubsystem, shooterSubsystem, transportSubsystem));
200+
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))));
201+
// operatorController.share().onTrue(transportSubsystem.setVoltageCommand(6.0).until(transportSubsystem::atSensor));
202+
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))));
203203
}
204204

205205
private void configureDriving() {

src/main/java/frc/robot/subsystems/elevator/ElevatorSubsystem.java

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -118,7 +118,7 @@ private void configMotors() {
118118
}
119119

120120
public void atBottomLimit() {
121-
if (bottomLimit.get()) {
121+
if (!bottomLimit.get()) {
122122
elevatorEncoder.setPosition(0);
123123
}
124124
}
@@ -175,15 +175,15 @@ public Command sysIdDynamic(SysIdRoutine.Direction direction) {
175175
@Override
176176
public void periodic() {
177177
// TODO: make this or elegant
178-
if (bottomLimit.get()) {
178+
if (!bottomLimit.get()) {
179179
elevatorEncoder.setPosition(0.0);
180180
}
181181
logValues();
182182
}
183183

184184
private void logValues() {
185185
elevatorMotor.logValues();
186-
bottomLimitEntry.append(bottomLimit.get());
186+
bottomLimitEntry.append(!bottomLimit.get());
187187

188188
if (FF_GAINS.hasChanged()) {
189189
feedforward = FF_GAINS.createElevatorFeedforward();

src/main/java/frc/robot/subsystems/shooter/ShooterSubsystem.java

Lines changed: 9 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -7,6 +7,7 @@
77
import com.revrobotics.CANSparkMax;
88
import com.revrobotics.RelativeEncoder;
99
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
10+
import edu.wpi.first.math.util.Units;
1011
import edu.wpi.first.wpilibj2.command.Command;
1112
import edu.wpi.first.wpilibj2.command.SubsystemBase;
1213
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine;
@@ -43,7 +44,7 @@ public class ShooterSubsystem extends SubsystemBase {
4344
private final SimpleMotorFeedforward feedforward = SHOOTER_FF_GAINS.createFeedforward();
4445

4546
private final DoubleTelemetryEntry flyVoltageReq =
46-
new DoubleTelemetryEntry("/shooter/voltageReq", false);
47+
new DoubleTelemetryEntry("/shooter/voltageReq", true);
4748
private final EventTelemetryEntry shooterEventEntry = new EventTelemetryEntry("/shooter/events");
4849

4950
public ShooterSubsystem() {
@@ -115,16 +116,21 @@ public void setVoltage(double voltage) {
115116
flywheelMotor.setVoltage(voltage);
116117
}
117118

119+
public double getVelocity() {
120+
return flywheelEncoder.getVelocity();
121+
}
122+
118123
public Command setVoltageCommand(double voltage) {
119124
return this.run(() -> setVoltage(voltage));
120125
}
121126

122127
public Command runVelocityCommand(double setpointRotationsPerSecond) {
128+
double radiansPerSecond = Units.rotationsToRadians(setpointRotationsPerSecond);
123129
return this.run(
124130
() ->
125131
setVoltage(
126-
pidController.calculate(flywheelEncoder.getVelocity(), setpointRotationsPerSecond)
127-
+ feedforward.calculate(setpointRotationsPerSecond)));
132+
pidController.calculate(flywheelEncoder.getVelocity(), radiansPerSecond)
133+
+ feedforward.calculate(radiansPerSecond)));
128134
}
129135

130136
public Command sysIdQuasistatic(SysIdRoutine.Direction direction) {

src/main/java/frc/robot/subsystems/transport/TransportSubsystem.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -86,7 +86,7 @@ public void configMotor() {
8686
}
8787

8888
public boolean atSensor() {
89-
return shooterSensor.get();
89+
return !shooterSensor.get();
9090
}
9191

9292
public Command runTransportOutCommand() {

0 commit comments

Comments
 (0)