Skip to content

Commit c57aa01

Browse files
committed
gains
1 parent b02b668 commit c57aa01

4 files changed

Lines changed: 32 additions & 17 deletions

File tree

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

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -5,12 +5,12 @@ public final class BuildConstants {
55
public static final String MAVEN_GROUP = "";
66
public static final String MAVEN_NAME = "2024RobotCode";
77
public static final String VERSION = "unspecified";
8-
public static final int GIT_REVISION = 304;
9-
public static final String GIT_SHA = "5bc910513e7bcfd602293d83b68b6e352918016c";
10-
public static final String GIT_DATE = "2024-07-26 18:58:28 EDT";
8+
public static final int GIT_REVISION = 306;
9+
public static final String GIT_SHA = "b02b6688c07f40ee3a6f56285b1df4f73fe24988";
10+
public static final String GIT_DATE = "2024-07-27 08:11:16 EDT";
1111
public static final String GIT_BRANCH = "rainbow-rumble";
12-
public static final String BUILD_DATE = "2024-07-26 18:59:58 EDT";
13-
public static final long BUILD_UNIX_TIME = 1722034798371L;
12+
public static final String BUILD_DATE = "2024-07-27 09:04:40 EDT";
13+
public static final long BUILD_UNIX_TIME = 1722085480261L;
1414
public static final int DIRTY = 1;
1515

1616
private BuildConstants() {}

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

Lines changed: 5 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -41,7 +41,6 @@
4141
import frc.robot.commands.AngleShooter;
4242
import frc.robot.commands.AngleShooterShoot;
4343
import frc.robot.commands.DriveCommands;
44-
import frc.robot.commands.DriveToChain;
4544
import frc.robot.commands.PivotIntakeAuto;
4645
import frc.robot.commands.PivotIntakeTele;
4746
import frc.robot.commands.PositionNoteInFeeder;
@@ -571,7 +570,11 @@ private void testControls() {
571570

572571
// driveController.a().whileTrue(new TurnToSource(drive, driveController));
573572

574-
driveController.a().whileTrue(new DriveToChain(drive));
573+
// driveController.a().whileTrue(new DriveToChain(drive));
574+
driveController.a().onTrue(new InstantCommand(() -> shooter.setFlywheelRPMs(5000, 5000)));
575+
driveController.a().onFalse(new InstantCommand(() -> shooter.stopFlywheels()));
576+
577+
driveController.x().onTrue(new SetPivotTarget(90, pivot));
575578
// manipController
576579
// .a()
577580
// .onTrue(

src/main/java/frc/robot/commands/TurnToAmpCorner.java

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -71,7 +71,7 @@ public TurnToAmpCorner(
7171
@Override
7272
public void initialize() {
7373
pivot.setPivotGoal(45);
74-
shooter.setFlywheelRPMs(5000, 4600);
74+
shooter.setFlywheelRPMs(5000, 4400);
7575
}
7676

7777
// Called every time the scheduler runs while the command is scheduled.
@@ -145,7 +145,7 @@ public void execute() {
145145
// Called once the command ends or is interrupted.
146146
@Override
147147
public void end(boolean interrupted) {
148-
shooter.setFeedersRPM(500);
148+
shooter.setFeedersRPM(3538);
149149
}
150150

151151
// Returns true when the command should end.

src/main/java/frc/robot/subsystems/Shooter/Shooter.java

Lines changed: 20 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -44,12 +44,12 @@ public Shooter(
4444
FlywheelIO flywheels, FeederIO feeder, DistanceSensorIO dist, LeafBlowerIO leafBlower) {
4545
switch (Constants.getMode()) {
4646
case REAL:
47-
leftFlywheelFFModel = new SimpleMotorFeedforward(0, 0.25, 0); // make constant
48-
rightFlywheelFFModel = new SimpleMotorFeedforward(0.18, 0.3);
47+
leftFlywheelFFModel = new SimpleMotorFeedforward(0.23, 0.18, 0); // make constant
48+
rightFlywheelFFModel = new SimpleMotorFeedforward(0.4, 0.5, 0.3);
4949

5050
feederFFModel = new SimpleMotorFeedforward(0, 0, 0);
5151

52-
flywheelkP.initDefault(0.9312); // make constant
52+
flywheelkP.initDefault(2.056); // make constant
5353
flywheelkI.initDefault(0);
5454
flywheelkD.initDefault(0);
5555

@@ -67,7 +67,7 @@ public Shooter(
6767
leftFlywheelFFModel = new SimpleMotorFeedforward(0, 0.5);
6868
rightFlywheelFFModel = new SimpleMotorFeedforward(0.18, 0.3);
6969

70-
feederFFModel = new SimpleMotorFeedforward(0, 0.58);
70+
feederFFModel = new SimpleMotorFeedforward(0, 0.5);
7171

7272
flywheelkP.initDefault(0.4); // make constant
7373
flywheelkI.initDefault(0);
@@ -118,20 +118,32 @@ public void setFlywheelRPMs(double leftVelocityRPM, double rightVelocityRPM) {
118118
public void setFlywheelRPMSSource() {
119119
if (DriverStation.getAlliance().get() == Alliance.Blue) {
120120
flywheels.setVelocityRPS(
121-
5000, 4200, leftFlywheelFFModel.calculate(5000 / 60.), leftFlywheelFFModel.calculate(4200 / 60.));
121+
5000,
122+
4200,
123+
leftFlywheelFFModel.calculate(5000 / 60.),
124+
leftFlywheelFFModel.calculate(4200 / 60.));
122125
} else {
123126
flywheels.setVelocityRPS(
124-
4200, 5000, leftFlywheelFFModel.calculate(5000 / 60.), leftFlywheelFFModel.calculate(4200 / 60.));
127+
4200,
128+
5000,
129+
leftFlywheelFFModel.calculate(5000 / 60.),
130+
leftFlywheelFFModel.calculate(4200 / 60.));
125131
}
126132
}
127133

128134
public void setFlywheelRPMSAmp() {
129135
if (DriverStation.getAlliance().get() == Alliance.Blue) {
130136
flywheels.setVelocityRPS(
131-
4200, 5000, leftFlywheelFFModel.calculate(4200 / 60.), leftFlywheelFFModel.calculate(5000 / 60.));
137+
4200,
138+
5000,
139+
leftFlywheelFFModel.calculate(4200 / 60.),
140+
leftFlywheelFFModel.calculate(5000 / 60.));
132141
} else {
133142
flywheels.setVelocityRPS(
134-
5000, 4200, leftFlywheelFFModel.calculate(5000 / 60.), leftFlywheelFFModel.calculate(4200 / 60.));
143+
5000,
144+
4200,
145+
leftFlywheelFFModel.calculate(5000 / 60.),
146+
leftFlywheelFFModel.calculate(4200 / 60.));
135147
}
136148
}
137149

0 commit comments

Comments
 (0)