Skip to content

Commit 1777ba5

Browse files
committed
SLAPDOWN IS SOOOO GOOD
1 parent 142348d commit 1777ba5

File tree

2 files changed

+23
-12
lines changed

2 files changed

+23
-12
lines changed

src/main/java/frc/robot/Constants.java

Lines changed: 12 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -46,12 +46,20 @@ public static class SlapdownConstants {
4646
public static final int ROTATION_STALL_MOTOR_CURRENT = 20;
4747
public static final int ROTATION_FREE_MOTOR_CURRENT = 10;
4848

49+
public static final double ROTATION_UP_ANGLE = Units.degreesToRadians(-24.404689 - 90.0);
50+
public static final double ROTATION_DOWN_ANGLE =
51+
ROTATION_UP_ANGLE + Units.degreesToRadians(128.817943);
52+
53+
public static final int ROTATION_LIMIT_SWITCH_ID = 0;
54+
4955
public static final TunablePIDGains ROTATION_GAINS =
50-
new TunablePIDGains("/slapdown/rotation/gains", 0, 0, 0, true);
56+
new TunablePIDGains("/slapdown/rotation/gains", 0, 0, 0, MiscConstants.TUNING_MODE);
5157
public static final TunableTrapezoidalProfileGains ROTATION_TRAP_GAINS =
52-
new TunableTrapezoidalProfileGains("/slapdown/rotation/trapGains", 0, 0, true);
53-
public static final TunableFFGains ROTATION_FF_GAINS =
54-
new TunableFFGains("/slapdown/rotation/FFGains", 0, 0, 0, true);
58+
new TunableTrapezoidalProfileGains(
59+
"/slapdown/rotation/trapGains", 0, 0, MiscConstants.TUNING_MODE);
60+
public static final TunableArmElevatorFFGains ROTATION_FF_GAINS =
61+
new TunableArmElevatorFFGains(
62+
"/slapdown/rotation/FFGains", 0, 0, 0, 0, MiscConstants.TUNING_MODE);
5563
}
5664

5765
public static class ElevatorConstants {

src/main/java/frc/robot/subsystems/slapdown/SlapdownSubsystem.java

Lines changed: 11 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -6,15 +6,15 @@
66
import com.revrobotics.CANSparkBase.IdleMode;
77
import com.revrobotics.CANSparkLowLevel.MotorType;
88
import com.revrobotics.RelativeEncoder;
9-
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
9+
import edu.wpi.first.math.controller.ArmFeedforward;
1010
import edu.wpi.first.math.geometry.Rotation2d;
1111
import edu.wpi.first.math.trajectory.TrapezoidProfile;
12+
import edu.wpi.first.wpilibj.DigitalInput;
1213
import edu.wpi.first.wpilibj2.command.Command;
1314
import edu.wpi.first.wpilibj2.command.SubsystemBase;
1415
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine;
1516
import frc.robot.Constants;
1617
import frc.robot.telemetry.tunable.TunableTelemetryProfiledPIDController;
17-
import frc.robot.telemetry.types.DoubleTelemetryEntry;
1818
import frc.robot.telemetry.types.EventTelemetryEntry;
1919
import frc.robot.telemetry.wrappers.TelemetryCANSparkMax;
2020
import frc.robot.utils.Alert;
@@ -28,8 +28,6 @@ public class SlapdownSubsystem extends SubsystemBase {
2828
private static final Alert feederMotorAlert =
2929
new Alert("Slapdown feeder motor had a fault initializing", Alert.AlertType.ERROR);
3030

31-
private DoubleTelemetryEntry rotationEncoderEntry =
32-
new DoubleTelemetryEntry("/slapdown/encoders", true);
3331
private final TelemetryCANSparkMax feederMotor =
3432
new TelemetryCANSparkMax(
3533
FEEDER_MOTOR_ID,
@@ -42,6 +40,7 @@ public class SlapdownSubsystem extends SubsystemBase {
4240
MotorType.kBrushless,
4341
"/slapdown/rotation/motor",
4442
Constants.MiscConstants.TUNING_MODE);
43+
4544
private final SysIdRoutine slapdownRotationSysId =
4645
new SysIdRoutine(
4746
new SysIdRoutine.Config(),
@@ -50,18 +49,20 @@ public class SlapdownSubsystem extends SubsystemBase {
5049
null, // No log consumer, since data is recorded by URCL
5150
this));
5251

53-
private final SimpleMotorFeedforward rotationFF;
52+
private final ArmFeedforward rotationFF = ROTATION_FF_GAINS.createArmFeedforward();
5453
private final TunableTelemetryProfiledPIDController rotationController =
5554
new TunableTelemetryProfiledPIDController(
5655
"/slapdown/rotation/controller", ROTATION_GAINS, ROTATION_TRAP_GAINS);
56+
5757
private final RelativeEncoder rotationEncoder;
5858

59+
private final DigitalInput rotationLimitSwitch = new DigitalInput(ROTATION_LIMIT_SWITCH_ID);
60+
5961
private final EventTelemetryEntry slapdownEventEntry =
6062
new EventTelemetryEntry("/slapdown/events");
6163

6264
public SlapdownSubsystem() {
6365
rotationEncoder = rotationMotor.getEncoder();
64-
rotationFF = ROTATION_FF_GAINS.createFeedforward();
6566
configMotors();
6667

6768
setDefaultCommand(stopAllCommand());
@@ -226,9 +227,11 @@ public Command stopAllCommand() {
226227

227228
@Override
228229
public void periodic() {
230+
if (rotationLimitSwitch.get()) {
231+
rotationEncoder.setPosition(ROTATION_UP_ANGLE);
232+
}
233+
229234
rotationMotor.logValues();
230235
feederMotor.logValues();
231-
232-
rotationEncoderEntry.append(getPosition());
233236
}
234237
}

0 commit comments

Comments
 (0)