Skip to content

Commit 001420c

Browse files
committed
2 parents 92d272f + 98b34d2 commit 001420c

File tree

8 files changed

+161
-23
lines changed

8 files changed

+161
-23
lines changed

gradlew

100644100755
File mode changed.
Lines changed: 92 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,94 @@
11
package frc.robot.constants;
22

3-
public class AlgaeConstants {}
3+
import static edu.wpi.first.units.Units.Degrees;
4+
import static edu.wpi.first.units.Units.Rotations;
5+
6+
import com.ctre.phoenix6.configs.CurrentLimitsConfigs;
7+
import com.ctre.phoenix6.configs.HardwareLimitSwitchConfigs;
8+
import com.ctre.phoenix6.configs.MotionMagicConfigs;
9+
import com.ctre.phoenix6.configs.MotorOutputConfigs;
10+
import com.ctre.phoenix6.configs.Slot0Configs;
11+
import com.ctre.phoenix6.configs.SoftwareLimitSwitchConfigs;
12+
import com.ctre.phoenix6.configs.TalonFXConfiguration;
13+
import com.ctre.phoenix6.signals.ForwardLimitSourceValue;
14+
import com.ctre.phoenix6.signals.ForwardLimitTypeValue;
15+
import com.ctre.phoenix6.signals.GravityTypeValue;
16+
import com.ctre.phoenix6.signals.NeutralModeValue;
17+
import com.ctre.phoenix6.signals.ReverseLimitSourceValue;
18+
import com.ctre.phoenix6.signals.ReverseLimitTypeValue;
19+
import edu.wpi.first.units.measure.*;
20+
21+
public class AlgaeConstants {
22+
23+
public static int kFxId = 4; // CHANGE TO MOTOR NUMBER
24+
25+
public static final Angle kCloseEnough = Degrees.of(5);
26+
public static final Angle kMaxFwd = Rotations.of(100);
27+
public static final Angle kMaxRev = Rotations.of(-100);
28+
public static final Angle kZeroTicks = Rotations.of(1530);
29+
30+
// Example Talon FX Config
31+
public static TalonFXConfiguration getFXConfig() {
32+
TalonFXConfiguration fxConfig = new TalonFXConfiguration();
33+
34+
CurrentLimitsConfigs current =
35+
new CurrentLimitsConfigs()
36+
.withStatorCurrentLimit(10)
37+
.withStatorCurrentLimitEnable(false)
38+
.withStatorCurrentLimit(20)
39+
.withSupplyCurrentLimit(10)
40+
.withSupplyCurrentLowerLimit(8)
41+
.withSupplyCurrentLowerTime(0.02)
42+
.withSupplyCurrentLimitEnable(true);
43+
fxConfig.CurrentLimits = current;
44+
45+
HardwareLimitSwitchConfigs hwLimit =
46+
new HardwareLimitSwitchConfigs()
47+
.withForwardLimitAutosetPositionEnable(false)
48+
.withForwardLimitEnable(false)
49+
.withForwardLimitType(ForwardLimitTypeValue.NormallyOpen)
50+
.withForwardLimitSource(ForwardLimitSourceValue.LimitSwitchPin)
51+
.withReverseLimitAutosetPositionEnable(false)
52+
.withReverseLimitEnable(false)
53+
.withReverseLimitType(ReverseLimitTypeValue.NormallyOpen)
54+
.withReverseLimitSource(ReverseLimitSourceValue.LimitSwitchPin);
55+
fxConfig.HardwareLimitSwitch = hwLimit;
56+
57+
SoftwareLimitSwitchConfigs swLimit =
58+
new SoftwareLimitSwitchConfigs()
59+
.withForwardSoftLimitEnable(true)
60+
.withForwardSoftLimitThreshold(kMaxFwd)
61+
.withReverseSoftLimitEnable(true)
62+
.withReverseSoftLimitThreshold(kMaxRev);
63+
fxConfig.SoftwareLimitSwitch = swLimit;
64+
65+
Slot0Configs slot0 =
66+
new Slot0Configs()
67+
.withKP(0)
68+
.withKI(0)
69+
.withKD(0)
70+
.withGravityType(GravityTypeValue.Elevator_Static)
71+
.withKG(0)
72+
.withKS(0)
73+
.withKV(0)
74+
.withKA(0);
75+
fxConfig.Slot0 = slot0;
76+
77+
MotionMagicConfigs motionMagic =
78+
new MotionMagicConfigs()
79+
.withMotionMagicAcceleration(0)
80+
.withMotionMagicCruiseVelocity(0)
81+
.withMotionMagicExpo_kA(0)
82+
.withMotionMagicExpo_kV(0)
83+
.withMotionMagicJerk(0);
84+
fxConfig.MotionMagic = motionMagic;
85+
86+
MotorOutputConfigs motorOut =
87+
new MotorOutputConfigs()
88+
.withDutyCycleNeutralDeadband(0.01)
89+
.withNeutralMode(NeutralModeValue.Coast);
90+
fxConfig.MotorOutput = motorOut;
91+
92+
return fxConfig;
93+
}
94+
}
Lines changed: 20 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,20 @@
1+
package frc.robot.subsystems.algae;
2+
3+
import edu.wpi.first.units.measure.AngularVelocity;
4+
import org.littletonrobotics.junction.AutoLog;
5+
import org.strykeforce.telemetry.TelemetryService;
6+
7+
public interface algaeIO {
8+
@AutoLog
9+
public static class IOInputs {
10+
public AngularVelocity velocity;
11+
}
12+
13+
public default void updateInputs(IOInputs inputs) {}
14+
15+
public default void setPosition(double position) {}
16+
17+
public default void zero() {}
18+
19+
public default void registerWith(TelemetryService telemetryService) {}
20+
}
Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,3 @@
1+
package frc.robot.subsystems.algae;
2+
3+
public class algaeIOFX {}

src/main/java/frc/robot/subsystems/example/ExampleIO.java

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -7,6 +7,7 @@
77
import edu.wpi.first.units.measure.AngularVelocity;
88
import org.littletonrobotics.junction.AutoLog;
99
// import org.strykeforce.telemetry.TelemetryService;
10+
import org.strykeforce.telemetry.TelemetryService;
1011

1112
public interface ExampleIO {
1213

@@ -22,5 +23,5 @@ public default void setPosition(Angle position) {}
2223

2324
public default void zero() {}
2425

25-
// public default void registerWith(TelemetryService telemetryService) {}
26+
public default void registerWith(TelemetryService telemetryService) {}
2627
}

src/main/java/frc/robot/subsystems/example/ExampleIOFX.java

Lines changed: 9 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,6 @@
11
package frc.robot.subsystems.example;
22

3+
import com.ctre.phoenix6.BaseStatusSignal;
34
import com.ctre.phoenix6.StatusSignal;
45
import com.ctre.phoenix6.configs.TalonFXConfiguration;
56
import com.ctre.phoenix6.configs.TalonFXConfigurator;
@@ -10,7 +11,7 @@
1011
import frc.robot.constants.ExampleConstants;
1112
import org.slf4j.Logger;
1213
import org.slf4j.LoggerFactory;
13-
// import org.strykeforce.telemetry.TelemetryService;
14+
import org.strykeforce.telemetry.TelemetryService;
1415

1516
public class ExampleIOFX implements ExampleIO {
1617
// private objects
@@ -63,12 +64,13 @@ public void setPosition(Angle position) {
6364

6465
@Override
6566
public void updateInputs(ExampleIOInputs inputs) {
66-
inputs.velocity = currVelocity.refresh().getValue();
67-
inputs.position = currPosition.refresh().getValue().minus(relSetpointOffset);
67+
BaseStatusSignal.refreshAll(currVelocity, currPosition);
68+
inputs.velocity = currVelocity.getValue();
69+
inputs.position = currPosition.getValue().minus(relSetpointOffset);
6870
}
6971

70-
// @Override
71-
// public void registerWith(TelemetryService telemetryService) {
72-
// telemetryService.register(talonFx, true);
73-
// }
72+
@Override
73+
public void registerWith(TelemetryService telemetryService) {
74+
telemetryService.register(talonFx, true);
75+
}
7476
}

src/main/java/frc/robot/subsystems/example/ExampleSubsystem.java

Lines changed: 15 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -3,15 +3,15 @@
33
import static edu.wpi.first.units.Units.Rotations;
44

55
import edu.wpi.first.units.measure.Angle;
6-
import edu.wpi.first.wpilibj2.command.SubsystemBase;
76
import frc.robot.constants.ExampleConstants;
87
import frc.robot.standards.ClosedLoopPosSubsystem;
8+
import java.util.Set;
99
import org.littletonrobotics.junction.Logger;
10-
// import org.strykeforce.telemetry.TelemetryService;
11-
// import org.strykeforce.telemetry.measurable.MeasurableSubsystem;
12-
// import org.strykeforce.telemetry.measurable.Measure;
10+
import org.strykeforce.telemetry.TelemetryService;
11+
import org.strykeforce.telemetry.measurable.MeasurableSubsystem;
12+
import org.strykeforce.telemetry.measurable.Measure;
1313

14-
public class ExampleSubsystem extends SubsystemBase implements ClosedLoopPosSubsystem {
14+
public class ExampleSubsystem extends MeasurableSubsystem implements ClosedLoopPosSubsystem {
1515
// Private Variables
1616
private final ExampleIO io;
1717
private final ExampleIOInputsAutoLogged inputs = new ExampleIOInputsAutoLogged();
@@ -58,6 +58,7 @@ public boolean isFinished() {
5858
public void periodic() {
5959
// Read Inputs
6060
io.updateInputs(inputs);
61+
Logger.processInputs(getName(), inputs);
6162

6263
// State Machine
6364
switch (curState) {
@@ -75,17 +76,17 @@ public void periodic() {
7576
}
7677

7778
// Grapher
78-
// @Override
79-
// public void registerWith(TelemetryService telemetryService) {
79+
@Override
80+
public void registerWith(TelemetryService telemetryService) {
8081

81-
// super.registerWith(telemetryService);
82-
// io.registerWith(telemetryService);
83-
// }
82+
super.registerWith(telemetryService);
83+
io.registerWith(telemetryService);
84+
}
8485

85-
// @Override
86-
// public Set<Measure> getMeasures() {
87-
// return Set.of(new Measure("State", () -> curState.ordinal()));
88-
// }
86+
@Override
87+
public Set<Measure> getMeasures() {
88+
return Set.of(new Measure("State", () -> curState.ordinal()));
89+
}
8990

9091
// State Enum
9192
public enum ExampleState {

vendordeps/thirdcoast.json

Lines changed: 20 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,20 @@
1+
{
2+
"fileName": "thirdcoast.json",
3+
"name": "StrykeForce-ThirdCoast",
4+
"version": "25.0.0",
5+
"uuid": "13c4f4b5-a1c0-4670-8f8d-b7b03628c0d3",
6+
"frcYear": "2025",
7+
"mavenUrls": [
8+
"https://s3.us-east-2.amazonaws.com/packages.strykeforce.org/repo/"
9+
],
10+
"jsonUrl": "https://s3.us-east-2.amazonaws.com/packages.strykeforce.org/thirdcoast.json",
11+
"javaDependencies": [
12+
{
13+
"groupId": "org.strykeforce",
14+
"artifactId": "thirdcoast",
15+
"version": "25.0.0"
16+
}
17+
],
18+
"jniDependencies": [],
19+
"cppDependencies": []
20+
}

0 commit comments

Comments
 (0)