Skip to content

Commit 0c5e954

Browse files
authored
Merge pull request #46 from strykeforce/auto-align-climb
New Algae End Effector, Gyro Fixes
2 parents 724ff87 + 8a914fa commit 0c5e954

19 files changed

+424
-143
lines changed

build.gradle

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -81,7 +81,7 @@ dependencies {
8181

8282
implementation 'ch.qos.logback:logback-classic:1.3.5' //logging
8383
implementation("com.opencsv:opencsv:5.6")
84-
implementation 'org.strykeforce:wallEYE:25.0.1'
84+
implementation 'org.strykeforce:wallEYE:25.1.0'
8585
implementation 'net.jafama:jafama:2.3.2' //fastMath
8686
}
8787

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

Lines changed: 18 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -28,6 +28,7 @@
2828
import frc.robot.commands.biscuit.HoldBiscuitCommand;
2929
import frc.robot.commands.biscuit.JogBiscuitCommand;
3030
import frc.robot.commands.biscuit.ZeroBiscuitCommand;
31+
import frc.robot.commands.climb.AutoClimbCommand;
3132
import frc.robot.commands.climb.ClimbCommand;
3233
import frc.robot.commands.climb.ClimbPrepCommand;
3334
import frc.robot.commands.coral.EnableEjectBeamCommand;
@@ -70,6 +71,7 @@
7071
import frc.robot.subsystems.battMon.BattMonSubsystem;
7172
import frc.robot.subsystems.biscuit.BiscuitIOFXS;
7273
import frc.robot.subsystems.biscuit.BiscuitSubsystem;
74+
import frc.robot.subsystems.climb.ClimbAlignSubsystem;
7375
import frc.robot.subsystems.climb.ClimbIO;
7476
import frc.robot.subsystems.climb.ClimbIOServoFX;
7577
import frc.robot.subsystems.climb.ClimbSubsystem;
@@ -109,6 +111,7 @@ public class RobotContainer {
109111

110112
private final ClimbIO climbIO;
111113
private final ClimbSubsystem climbSubsystem;
114+
private final ClimbAlignSubsystem climbAlignSubsystem;
112115

113116
private final CoralIOFX coralIO;
114117
private final CoralSubsystem coralSubsystem;
@@ -170,6 +173,7 @@ public RobotContainer() {
170173
protoSwerve = new Swerve();
171174
driveSubsystem = new DriveSubsystem(protoSwerve);
172175
}
176+
climbAlignSubsystem = new ClimbAlignSubsystem(climbSubsystem, driveSubsystem);
173177

174178
elevatorIO = new ElevatorIOFX();
175179
elevatorSubsystem = new ElevatorSubsystem(elevatorIO);
@@ -190,6 +194,7 @@ public RobotContainer() {
190194
battMonSubsystem,
191195
biscuitSubsystem,
192196
climbSubsystem,
197+
climbAlignSubsystem,
193198
coralSubsystem,
194199
driveSubsystem,
195200
elevatorSubsystem,
@@ -658,6 +663,11 @@ public void configTestDash() {
658663
.withPosition(1, 0)
659664
.withSize(1, 1);
660665

666+
Shuffleboard.getTab("Test")
667+
.addDouble("Yaw Camera Idx", () -> visionSubsystem.getYawUpdateCamera())
668+
.withPosition(1, 1)
669+
.withSize(1, 1);
670+
661671
// Shuffleboard.getTab("Test")
662672
// .add("Start Auton", nonProcessorShallowAutonCommand)
663673
// .withPosition(3, 0)
@@ -685,6 +695,14 @@ public void configTestDash() {
685695
.add("Set isAuto True", new InstantCommand(() -> robotStateSubsystem.setIsAuto(true)))
686696
.withPosition(7, 0)
687697
.withSize(1, 1);
698+
699+
Shuffleboard.getTab("Test")
700+
.add(
701+
"Auto Climb",
702+
new AutoClimbCommand(
703+
driveSubsystem, climbSubsystem, climbAlignSubsystem, robotStateSubsystem))
704+
.withPosition(0, 1)
705+
.withSize(1, 1);
688706
}
689707

690708
public Command getAutonomousCommand() {
Lines changed: 43 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,43 @@
1+
package frc.robot.commands.climb;
2+
3+
import edu.wpi.first.wpilibj2.command.Command;
4+
import frc.robot.subsystems.climb.ClimbAlignSubsystem;
5+
import frc.robot.subsystems.climb.ClimbAlignSubsystem.ClimbAlignStates;
6+
import frc.robot.subsystems.climb.ClimbSubsystem;
7+
import frc.robot.subsystems.climb.ClimbSubsystem.ClimbState;
8+
import frc.robot.subsystems.drive.DriveSubsystem;
9+
import frc.robot.subsystems.robotState.RobotStateSubsystem;
10+
11+
public class AutoClimbCommand extends Command {
12+
private ClimbSubsystem climbSubsystem;
13+
private ClimbAlignSubsystem climbAlignSubsystem;
14+
private RobotStateSubsystem robotStateSubsystem;
15+
16+
public AutoClimbCommand(
17+
DriveSubsystem driveSubsystem,
18+
ClimbSubsystem climbSubsystem,
19+
ClimbAlignSubsystem climbAlignSubsystem,
20+
RobotStateSubsystem robotStateSubsystem) {
21+
this.climbAlignSubsystem = climbAlignSubsystem;
22+
this.robotStateSubsystem = robotStateSubsystem;
23+
this.climbSubsystem = climbSubsystem;
24+
25+
addRequirements(climbSubsystem, driveSubsystem);
26+
}
27+
28+
@Override
29+
public void initialize() {
30+
climbAlignSubsystem.start(robotStateSubsystem.getAllianceColor());
31+
}
32+
33+
@Override
34+
public void end(boolean interrupted) {
35+
climbAlignSubsystem.terminate();
36+
}
37+
38+
@Override
39+
public boolean isFinished() {
40+
return climbAlignSubsystem.getState() == ClimbAlignStates.DONE
41+
&& climbSubsystem.getState() == ClimbState.CLIMBED;
42+
}
43+
}

src/main/java/frc/robot/commands/robotState/AutoReefCycleCommand.java

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -44,6 +44,7 @@ public void initialize() {
4444
@Override
4545
public void end(boolean interrupted) {
4646
tagAlignSubsystem.terminate();
47+
driveSubsystem.setIgnoreSticks(false);
4748
}
4849

4950
@Override

src/main/java/frc/robot/constants/BiscuitConstants.java

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -46,8 +46,8 @@ public class BiscuitConstants {
4646
// public static final Angle kBargeBackwardSetpoint = Rotations.of(-12.3489); // 9.089
4747

4848
// jogging
49-
public static final double kJogAmountUp = 10;
50-
public static final double kJogAmountDown = -10;
49+
public static final double kJogAmountUp = 3;
50+
public static final double kJogAmountDown = -3;
5151

5252
// Soft Limits
5353
// public static final Angle kMaxFwd = kMicAlgaeSetpoint.plus(Rotations.of(5));

src/main/java/frc/robot/constants/ClimbConstants.java

Lines changed: 17 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -43,9 +43,24 @@ public class ClimbConstants {
4343

4444
// Climb positions
4545
// public static final Angle kClimbCagePos = Rotations.of(); // will test
46-
public static final Double kClimbRatchedEngage = -0.12;
46+
public static final double kClimbRatchedEngage = -0.12;
4747
public static final double kFullyClimbed = kArmMaxFwd;
48-
public static final double kClimbOpenLoopSpeed = 4.0;
48+
public static final double kClimbOpenLoopSpeed = 3.0;
49+
50+
// Cage location info
51+
public static final double kCenterX = DriveConstants.kFieldMaxX / 2.0;
52+
public static final double kCenterY = DriveConstants.kFieldMaxY / 2.0;
53+
public static final double[] kCageOffsetY = {1.0541, 2.143125, 3.235325};
54+
public static final double kCageOffsetX = 1.2;
55+
56+
public static final double kClimbRobotOffset = 0.0075;
57+
58+
public static final double kFinalDriveVx = 0.25;
59+
public static final double kMaxDistX = 3;
60+
// Align end conditions
61+
public static final double kCloseEnoughX = 0.1;
62+
public static final double kCloseEnoughY = 0.03;
63+
public static final double kClimbAngleGood = RobotStateConstants.kClimbAngleSmall;
4964

5065
public static TalonFXConfiguration getPivotArmFxConfig() {
5166
TalonFXConfiguration armFxConfig = new TalonFXConfiguration();

src/main/java/frc/robot/constants/DriveConstants.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -45,7 +45,7 @@ public class DriveConstants {
4545
public static final double kMaxSpeedMetersPerSecond = 3.782;
4646
public static final double kSpeedStillThreshold = 0.1; // meters per second
4747
public static final double kGyroRateStillThreshold = 10.0; // 25 5 degrees per second
48-
public static final double kGyroDifferentThreshold = 5.0; // 5 degrees
48+
public static final double kGyroDifferentThreshold = 0.5; // 5 degrees
4949
public static final int kGyroDifferentCount = 3;
5050

5151
public static final double kRobotLength = 0.61595;

src/main/java/frc/robot/constants/ElevatorConstants.java

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -43,8 +43,8 @@ public class ElevatorConstants {
4343
// Idle
4444

4545
// Algae removal
46-
public static final Angle kL2AlgaeSetpoint = Rotations.of(5.826); // was 6.308
47-
public static final Angle kL3AlgaeSetpoint = Rotations.of(17.513);
46+
public static final Angle kL2AlgaeSetpoint = Rotations.of(6.3457); // was 6.308
47+
public static final Angle kL3AlgaeSetpoint = Rotations.of(17.428223);
4848

4949
public static final Angle kL2AlgaeRemovalSetpoint = kL2AlgaeSetpoint;
5050
public static final Angle kL3AlgaeRemovalSetpoint = kL3AlgaeSetpoint;
@@ -60,13 +60,13 @@ public class ElevatorConstants {
6060
public static final Angle kAutoPrestageSetpoint = kL4CoralSetpoint;
6161

6262
// Algae obtaining
63-
public static final Angle kFloorAlgaeSetpoint = Rotations.of(6.66);
64-
public static final Angle kMicAlgaeSetpoint = Rotations.of(17.07);
63+
public static final Angle kFloorAlgaeSetpoint = Rotations.of(5.82);
64+
public static final Angle kMicAlgaeSetpoint = Rotations.of(2.703);
6565
public static final Angle kHpAlgaeSetpoint = Rotations.of(14.9063);
6666

6767
// Algae scoring
68-
public static final Angle kProcessorSetpoint = Rotations.of(6.3215); // was 4.297 -> 5.964
69-
public static final Angle kBargeSetpoint = Rotations.of(44.943); // 41.936
68+
public static final Angle kProcessorSetpoint = Rotations.of(3.348); // was 4.297 -> 5.964
69+
public static final Angle kBargeSetpoint = Rotations.of(44.785); // 41.936
7070
public static final Angle kBargeHigherThan = Rotations.of(31.0901);
7171

7272
public static TalonFXConfiguration getBothFXConfig() {

src/main/java/frc/robot/constants/RobotConstants.java

Lines changed: 24 additions & 24 deletions
Original file line numberDiff line numberDiff line change
@@ -79,7 +79,7 @@ public class RobotConstants {
7979
// Algae scoring
8080
public static Angle kProcessorSetpoint;
8181
public static Angle kBargeSetpoint;
82-
public static Angle kBargeBackwardSetpoint;
82+
// public static Angle kBargeBackwardSetpoint;
8383

8484
public static double kTagAlignThreshold;
8585

@@ -108,7 +108,7 @@ public RobotConstants() {
108108
kStowSetpoint = CompConstants.kBiscuitStowSetpoint;
109109
kFunnelSetpoint = CompConstants.kFunnelSetpoint;
110110
kPrestageSetpoint = CompConstants.kPrestageSetpoint;
111-
kPrestageAlgaeSetpoint = CompConstants.kPrestageAlgaeSetpoint;
111+
kPrestageAlgaeSetpoint = CompConstants.kBiscuitStowSetpoint;
112112

113113
// Algae removal
114114
kL2AlgaeSetpoint = CompConstants.kL2AlgaeSetpoint;
@@ -131,7 +131,7 @@ public RobotConstants() {
131131
// Algae scoring
132132
kProcessorSetpoint = CompConstants.kProcessorSetpoint;
133133
kBargeSetpoint = CompConstants.kBargeSetpoint;
134-
kBargeBackwardSetpoint = CompConstants.kBargeBackwardSetpoint;
134+
// kBargeBackwardSetpoint = CompConstants.kBargeBackwardSetpoint;
135135
kTagAlignThreshold = CompConstants.kTagAlignThreshold;
136136
} else {
137137
// Proto constants
@@ -177,7 +177,7 @@ public RobotConstants() {
177177
// Algae scoring
178178
kProcessorSetpoint = ProtoConstants.kProcessorSetpoint;
179179
kBargeSetpoint = ProtoConstants.kBargeSetpoint;
180-
kBargeBackwardSetpoint = ProtoConstants.kBargeBackwardSetpoint;
180+
// kBargeBackwardSetpoint = ProtoConstants.kBargeBackwardSetpoint;
181181

182182
kTagAlignThreshold = ProtoConstants.kTagAlignThreshold;
183183
}
@@ -229,13 +229,13 @@ public static class ProtoConstants {
229229
// Algae scoring
230230
public static Angle kProcessorSetpoint = Rotations.of(41.193);
231231
public static Angle kBargeSetpoint = Rotations.of(12.3489);
232-
public static Angle kBargeBackwardSetpoint = Rotations.of(-12.3489); // 9.089
232+
// public static Angle kBargeBackwardSetpoint = Rotations.of(-12.3489); // 9.089
233233

234234
// Elevator
235235
public static Angle kElevatorFunnelSetpoint = Rotations.of(2.03125);
236236
public static Angle kElevatorStowSetpoint = kElevatorFunnelSetpoint;
237237
public static Angle kMaxFwd = kMicAlgaeSetpoint.plus(Rotations.of(5));
238-
public static Angle kMaxRev = kBargeBackwardSetpoint.minus(Rotations.of(5));
238+
public static Angle kMaxRev = kPrestageSetpoint.minus(Rotations.of(5));
239239

240240
public static MotionMagicConfigs getAlgaeMotionConfig() {
241241
MotionMagicConfigs algaeConfig =
@@ -343,36 +343,36 @@ public static class CompConstants {
343343
// Idle
344344
public static Angle kBiscuitStowSetpoint = Rotations.of(1.862 / 2);
345345
public static Angle kFunnelSetpoint = kBiscuitStowSetpoint;
346-
public static Angle kPrestageSetpoint = kBiscuitStowSetpoint;
347-
public static Angle kPrestageAlgaeSetpoint = Rotations.of(9.089 / 2);
346+
public static Angle kPrestageSetpoint = Rotations.of(-2.94);
347+
public static Angle kPrestageAlgaeSetpoint = kBiscuitStowSetpoint;
348348

349349
// Algae removal
350-
public static Angle kL2AlgaeSetpoint = Rotations.of(24.104 / 2);
351-
public static Angle kL3AlgaeSetpoint = Rotations.of(24.562 / 2);
350+
public static Angle kL2AlgaeSetpoint = Rotations.of(7.39);
351+
public static Angle kL3AlgaeSetpoint = Rotations.of(7.39);
352352

353-
public static Angle kL2AlgaeRemovalSetpoint = kBiscuitStowSetpoint;
354-
public static Angle kL3AlgaeRemovalSetpoint = kBiscuitStowSetpoint;
353+
public static Angle kL2AlgaeRemovalSetpoint = kPrestageSetpoint;
354+
public static Angle kL3AlgaeRemovalSetpoint = kPrestageSetpoint;
355355

356356
public static double kTagAlignThreshold = 20.0 / 2;
357357

358358
// Coral score
359-
public static Angle kL1CoralSetpoint = kBiscuitStowSetpoint;
360-
public static Angle kL2CoralSetpoint = kBiscuitStowSetpoint;
361-
public static Angle kL3CoralSetpoint = kBiscuitStowSetpoint;
362-
public static Angle kL4CoralSetpoint = kBiscuitStowSetpoint;
359+
public static Angle kL1CoralSetpoint = kPrestageSetpoint;
360+
public static Angle kL2CoralSetpoint = kPrestageSetpoint;
361+
public static Angle kL3CoralSetpoint = kPrestageSetpoint;
362+
public static Angle kL4CoralSetpoint = kPrestageSetpoint;
363363

364364
// Algae obtaining
365-
public static Angle kFloorAlgaeSetpoint = Rotations.of(49.627 / 2);
366-
public static Angle kMicAlgaeSetpoint = Rotations.of(51.61872 / 2);
367-
public static Angle kHpAlgaeSetpoint = Rotations.of(16.97559 / 2);
365+
public static Angle kFloorAlgaeSetpoint = Rotations.of(20.039);
366+
public static Angle kMicAlgaeSetpoint = Rotations.of(12.87085);
367+
public static Angle kHpAlgaeSetpoint = kBiscuitStowSetpoint;
368368

369369
// Algae scoring
370-
public static Angle kProcessorSetpoint = Rotations.of(41.193 / 2);
371-
public static Angle kBargeSetpoint = Rotations.of(12.3489 / 2);
372-
public static Angle kBargeBackwardSetpoint = Rotations.of(-12.3489 / 2); // 9.089
370+
public static Angle kProcessorSetpoint = Rotations.of(15.0139);
371+
public static Angle kBargeSetpoint = Rotations.of(2.697);
372+
// public static Angle kBargeBackwardSetpoint = Rotations.of(-12.3489 / 2); // 9.089
373373

374-
public static Angle kMaxFwd = kMicAlgaeSetpoint.plus(Rotations.of(5 / 2));
375-
public static Angle kMaxRev = kBargeBackwardSetpoint.minus(Rotations.of(5 / 2));
374+
public static Angle kMaxFwd = kFloorAlgaeSetpoint.plus(Rotations.of(5));
375+
public static Angle kMaxRev = kPrestageSetpoint.minus(Rotations.of(5));
376376

377377
public static MotionMagicConfigs getAlgaeMotionConfig() {
378378
MotionMagicConfigs algaeConfig =

src/main/java/frc/robot/constants/RobotStateConstants.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -7,7 +7,7 @@ public class RobotStateConstants {
77
public static final double kBlueBargeSafeX = 7.6;
88
public static final double kRedBargeSafeX = DriveConstants.kFieldMaxX - kBlueBargeSafeX;
99

10-
public static final double kCoralEjectTimer = 0.75;
10+
public static final double kCoralEjectTimer = 0.25;
1111
public static final double kAlgaeEjectTimer = 0.5;
1212

1313
public static final double kProcessorStowRadius = 0.5;

0 commit comments

Comments
 (0)