Skip to content

Commit fa0557c

Browse files
committedFeb 19, 2024
Implement Phoenix6 SysID
1 parent 572604f commit fa0557c

14 files changed

+506
-210
lines changed
 

‎build.gradle

+74-2
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,7 @@
11
plugins {
22
id "java"
3-
id "edu.wpi.first.GradleRIO" version "2024.1.1"
3+
id "edu.wpi.first.GradleRIO" version "2024.2.1"
4+
id 'com.diffplug.spotless' version '6.20.0'
45
}
56

67
java {
@@ -47,6 +48,27 @@ wpi.java.debugJni = false
4748
// Set this to true to enable desktop support.
4849
def includeDesktopSupport = true
4950

51+
repositories {
52+
maven {
53+
url = uri("https://maven.pkg.github.com/Mechanical-Advantage/AdvantageKit")
54+
credentials {
55+
username = "Mechanical-Advantage-Bot"
56+
password = "\u0067\u0068\u0070\u005f\u006e\u0056\u0051\u006a\u0055\u004f\u004c\u0061\u0079\u0066\u006e\u0078\u006e\u0037\u0051\u0049\u0054\u0042\u0032\u004c\u004a\u006d\u0055\u0070\u0073\u0031\u006d\u0037\u004c\u005a\u0030\u0076\u0062\u0070\u0063\u0051"
57+
}
58+
}
59+
mavenLocal()
60+
}
61+
62+
configurations.all {
63+
exclude group: "edu.wpi.first.wpilibj"
64+
}
65+
66+
task(checkAkitInstall, dependsOn: "classes", type: JavaExec) {
67+
mainClass = "org.littletonrobotics.junction.CheckInstall"
68+
classpath = sourceSets.main.runtimeClasspath
69+
}
70+
compileJava.finalizedBy checkAkitInstall
71+
5072
// Defining my dependencies. In this case, WPILib (+ friends), and vendor libraries.
5173
// Also defines JUnit 5.
5274
dependencies {
@@ -69,6 +91,9 @@ dependencies {
6991

7092
testImplementation 'org.junit.jupiter:junit-jupiter:5.10.1'
7193
testRuntimeOnly 'org.junit.platform:junit-platform-launcher'
94+
95+
def akitJson = new groovy.json.JsonSlurper().parseText(new File(projectDir.getAbsolutePath() + "/vendordeps/AdvantageKit.json").text)
96+
annotationProcessor "org.littletonrobotics.akit.junction:junction-autolog:$akitJson.version"
7297
}
7398

7499
test {
@@ -84,7 +109,11 @@ wpi.sim.addDriverstation()
84109
// in order to make them all available at runtime. Also adding the manifest so WPILib
85110
// knows where to look for our Robot Class.
86111
jar {
87-
from { configurations.runtimeClasspath.collect { it.isDirectory() ? it : zipTree(it) } }
112+
from {
113+
configurations.runtimeClasspath.collect {
114+
it.isDirectory() ? it : zipTree(it)
115+
}
116+
}
88117
from sourceSets.main.allSource
89118
manifest edu.wpi.first.gradlerio.GradleRIOPlugin.javaManifest(ROBOT_MAIN_CLASS)
90119
duplicatesStrategy = DuplicatesStrategy.INCLUDE
@@ -99,3 +128,46 @@ wpi.java.configureTestTasks(test)
99128
tasks.withType(JavaCompile) {
100129
options.compilerArgs.add '-XDstringConcat=inline'
101130
}
131+
132+
spotless {
133+
java {
134+
target fileTree('.') {
135+
include '**/*.java'
136+
exclude '**/build/**', '**/build-*/**'
137+
}
138+
toggleOffOn()
139+
googleJavaFormat()
140+
removeUnusedImports()
141+
trimTrailingWhitespace()
142+
endWithNewline()
143+
}
144+
groovyGradle {
145+
target fileTree('.') {
146+
include '**/*.gradle'
147+
exclude '**/build/**', '**/build-*/**'
148+
}
149+
greclipse()
150+
indentWithSpaces(4)
151+
trimTrailingWhitespace()
152+
endWithNewline()
153+
}
154+
format 'xml', {
155+
target fileTree('.') {
156+
include '**/*.xml'
157+
exclude '**/build/**', '**/build-*/**'
158+
}
159+
eclipseWtp('xml')
160+
trimTrailingWhitespace()
161+
indentWithSpaces(2)
162+
endWithNewline()
163+
}
164+
format 'misc', {
165+
target fileTree('.') {
166+
include '**/*.md', '**/.gitignore'
167+
exclude '**/build/**', '**/build-*/**'
168+
}
169+
trimTrailingWhitespace()
170+
indentWithSpaces(2)
171+
endWithNewline()
172+
}
173+
}

‎networktables.json

+1
Original file line numberDiff line numberDiff line change
@@ -0,0 +1 @@
1+
[]

‎simgui-ds.json

+92
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,92 @@
1+
{
2+
"keyboardJoysticks": [
3+
{
4+
"axisConfig": [
5+
{
6+
"decKey": 65,
7+
"incKey": 68
8+
},
9+
{
10+
"decKey": 87,
11+
"incKey": 83
12+
},
13+
{
14+
"decKey": 69,
15+
"decayRate": 0.0,
16+
"incKey": 82,
17+
"keyRate": 0.009999999776482582
18+
}
19+
],
20+
"axisCount": 3,
21+
"buttonCount": 4,
22+
"buttonKeys": [
23+
90,
24+
88,
25+
67,
26+
86
27+
],
28+
"povConfig": [
29+
{
30+
"key0": 328,
31+
"key135": 323,
32+
"key180": 322,
33+
"key225": 321,
34+
"key270": 324,
35+
"key315": 327,
36+
"key45": 329,
37+
"key90": 326
38+
}
39+
],
40+
"povCount": 1
41+
},
42+
{
43+
"axisConfig": [
44+
{
45+
"decKey": 74,
46+
"incKey": 76
47+
},
48+
{
49+
"decKey": 73,
50+
"incKey": 75
51+
}
52+
],
53+
"axisCount": 2,
54+
"buttonCount": 4,
55+
"buttonKeys": [
56+
77,
57+
44,
58+
46,
59+
47
60+
],
61+
"povCount": 0
62+
},
63+
{
64+
"axisConfig": [
65+
{
66+
"decKey": 263,
67+
"incKey": 262
68+
},
69+
{
70+
"decKey": 265,
71+
"incKey": 264
72+
}
73+
],
74+
"axisCount": 2,
75+
"buttonCount": 6,
76+
"buttonKeys": [
77+
260,
78+
268,
79+
266,
80+
261,
81+
269,
82+
267
83+
],
84+
"povCount": 0
85+
},
86+
{
87+
"axisCount": 0,
88+
"buttonCount": 0,
89+
"povCount": 0
90+
}
91+
]
92+
}

‎simgui.json

+10
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,10 @@
1+
{
2+
"NTProvider": {
3+
"types": {
4+
"/FMSInfo": "FMSInfo"
5+
}
6+
},
7+
"NetworkTables Info": {
8+
"visible": true
9+
}
10+
}
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,40 @@
1+
package frc.lib.sysid;
2+
3+
import com.ctre.phoenix6.SignalLogger;
4+
import edu.wpi.first.units.Measure;
5+
import edu.wpi.first.units.Time;
6+
import edu.wpi.first.units.Velocity;
7+
import edu.wpi.first.units.Voltage;
8+
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine;
9+
10+
public class SysIdRoutinePhoenixConfig {
11+
12+
/**
13+
* Create a new configuration for a SysId test routine.
14+
*
15+
* @param rampRate The voltage ramp rate used for quasistatic test routines. Defaults to 1 volt
16+
* per second if left null.
17+
* @param stepVoltage The step voltage output used for dynamic test routines. Defaults to 7 volts
18+
* if left null.
19+
* @param timeout Safety timeout for the test routine commands. Defaults to 10 seconds if left
20+
* null.
21+
* @param logName The name for the test routine in the log. Should be unique between complete test
22+
* routines (quasistatic and dynamic, forward and reverse). The current state of this test
23+
* (e.g. "quasistatic-forward") will appear in CTRE Log under the "sysid-test-state-logName"
24+
* signal.
25+
*/
26+
public static SysIdRoutine.Config get(
27+
Measure<Velocity<Voltage>> rampRate,
28+
Measure<Voltage> stepVoltage,
29+
Measure<Time> timeout,
30+
String logName) {
31+
return new SysIdRoutine.Config(
32+
rampRate,
33+
stepVoltage,
34+
timeout,
35+
recordState -> {
36+
SignalLogger.writeString("sysid-test-state-" + logName, recordState.toString());
37+
return;
38+
});
39+
}
40+
}

‎src/main/java/frc/robot/Interfaces/AngleMotorControl.java

+74-57
Original file line numberDiff line numberDiff line change
@@ -2,77 +2,94 @@
22
// Open Source Software; you can modify and/or share it under the terms of
33
// the WPILib BSD license file in the root directory of this project.
44

5-
package frc.robot.Interfaces;
5+
package frc.robot.interfaces;
66

7-
import com.ctre.phoenix6.controls.PositionDutyCycle;
7+
import com.ctre.phoenix6.configs.CANcoderConfiguration;
8+
import com.ctre.phoenix6.configs.TalonFXConfiguration;
9+
import com.ctre.phoenix6.controls.MotionMagicExpoVoltage;
810
import com.ctre.phoenix6.hardware.CANcoder;
911
import com.ctre.phoenix6.hardware.TalonFX;
10-
12+
import com.ctre.phoenix6.signals.AbsoluteSensorRangeValue;
13+
import com.ctre.phoenix6.signals.InvertedValue;
14+
import com.ctre.phoenix6.signals.NeutralModeValue;
15+
import com.ctre.phoenix6.signals.SensorDirectionValue;
1116
import edu.wpi.first.math.geometry.Rotation2d;
1217

1318
/** Add your docs here. */
1419
public class AngleMotorControl {
15-
public static TalonFX[] motor = new TalonFX[4];
16-
CANcoder[] CANcoder = new CANcoder[4];
1720

18-
public static final class Mod0 {
19-
public static final int angleMotorID = 12;
20-
public static final int canCoderID = 10;
21-
public static final Rotation2d angleOffset = Rotation2d.fromDegrees(117.334);
22-
}
21+
public static class ModConfig {
22+
public final int m_angleMotorID;
23+
public final int m_canCoderID;
24+
public final Rotation2d m_canCoderOffset;
2325

24-
/* Front Right Module - Module 1 */
25-
public static final class Mod1 {
26-
public static final int angleMotorID = 22;
27-
public static final int canCoderID = 20;
28-
public static final Rotation2d angleOffset = Rotation2d.fromDegrees(272.285);
29-
}
30-
31-
/* Back Left Module - Module 2 */
32-
public static final class Mod2 {
33-
public static final int angleMotorID = 32;
34-
public static final int canCoderID = 30;
35-
public static final Rotation2d angleOffset = Rotation2d.fromDegrees(248.906);
26+
public ModConfig(int angleMotorID, int canCoderID, Rotation2d canCoderOffset) {
27+
m_angleMotorID = angleMotorID;
28+
m_canCoderID = canCoderID;
29+
m_canCoderOffset = canCoderOffset;
3630
}
31+
}
3732

38-
/* Back Right Module - Module 3 */
39-
public static final class Mod3 {
40-
public static final int angleMotorID = 42;
41-
public static final int canCoderID = 40;
42-
public static final Rotation2d angleOffset = Rotation2d.fromDegrees(92.461);
43-
}
33+
public static final ModConfig[] m_modConfigs =
34+
new ModConfig[] {
35+
new ModConfig(12, 10, Rotation2d.fromDegrees(117.334)),
36+
new ModConfig(22, 20, Rotation2d.fromDegrees(272.285)),
37+
new ModConfig(32, 30, Rotation2d.fromDegrees(248.906)),
38+
new ModConfig(42, 40, Rotation2d.fromDegrees(92.461)),
39+
};
4440

45-
public AngleMotorControl() {
46-
motor[0] = new TalonFX(Mod0.angleMotorID);
47-
motor[1] = new TalonFX(Mod1.angleMotorID);
48-
motor[2] = new TalonFX(Mod2.angleMotorID);
49-
motor[3] = new TalonFX(Mod3.angleMotorID);
41+
public static final TalonFX[] m_angleMotors =
42+
new TalonFX[] {
43+
new TalonFX(m_modConfigs[0].m_angleMotorID),
44+
new TalonFX(m_modConfigs[1].m_angleMotorID),
45+
new TalonFX(m_modConfigs[2].m_angleMotorID),
46+
new TalonFX(m_modConfigs[3].m_angleMotorID),
47+
};
5048

51-
CANcoder[0] = new CANcoder(Mod0.canCoderID);
52-
CANcoder[1] = new CANcoder(Mod1.canCoderID);
53-
CANcoder[2] = new CANcoder(Mod2.canCoderID);
54-
CANcoder[3] = new CANcoder(Mod3.canCoderID);
49+
public static final CANcoder[] m_canCoders =
50+
new CANcoder[] {
51+
new CANcoder(m_modConfigs[0].m_canCoderID),
52+
new CANcoder(m_modConfigs[1].m_canCoderID),
53+
new CANcoder(m_modConfigs[2].m_canCoderID),
54+
new CANcoder(m_modConfigs[3].m_canCoderID),
55+
};
5556

56-
resetAnglePos();
57-
}
58-
public void resetAnglePos() {
59-
motor[0].setPosition(
60-
(Rotation2d.fromRotations(CANcoder[0].getAbsolutePosition().getValueAsDouble()).getDegrees()
61-
- Mod0.angleOffset.getDegrees())/ 360);
62-
motor[1].setPosition(
63-
(Rotation2d.fromRotations(CANcoder[1].getAbsolutePosition().getValueAsDouble()).getDegrees()
64-
- Mod0.angleOffset.getDegrees())/ 360);
65-
motor[2].setPosition(
66-
(Rotation2d.fromRotations(CANcoder[2].getAbsolutePosition().getValueAsDouble()).getDegrees()
67-
- Mod0.angleOffset.getDegrees())/ 360);
68-
motor[3].setPosition(
69-
(Rotation2d.fromRotations(CANcoder[3].getAbsolutePosition().getValueAsDouble()).getDegrees()
70-
- Mod0.angleOffset.getDegrees())/ 360);
57+
public AngleMotorControl() {
58+
TalonFXConfiguration angleMotorConfig = new TalonFXConfiguration();
59+
60+
angleMotorConfig.ClosedLoopGeneral.ContinuousWrap = true;
61+
angleMotorConfig.Feedback.SensorToMechanismRatio = 150.0 / 7.0;
62+
angleMotorConfig.MotionMagic.MotionMagicAcceleration = 1.0;
63+
angleMotorConfig.MotionMagic.MotionMagicCruiseVelocity = 1.0;
64+
angleMotorConfig.MotionMagic.MotionMagicExpo_kA = 0.17079;
65+
angleMotorConfig.MotionMagic.MotionMagicExpo_kV = 2.314285;
66+
angleMotorConfig.MotionMagic.MotionMagicJerk = 1.0;
67+
angleMotorConfig.Slot0.kS = 0.16992;
68+
angleMotorConfig.Slot0.kV = 2.314285;
69+
angleMotorConfig.Slot0.kA = 0.17079;
70+
angleMotorConfig.Slot0.kP = 107.142857;
71+
angleMotorConfig.Slot0.kI = 1.0;
72+
angleMotorConfig.Slot0.kD = 1.0;
73+
angleMotorConfig.MotorOutput.Inverted = InvertedValue.Clockwise_Positive;
74+
angleMotorConfig.MotorOutput.NeutralMode = NeutralModeValue.Coast;
75+
76+
CANcoderConfiguration canCoderConfig = new CANcoderConfiguration();
77+
78+
canCoderConfig.MagnetSensor.AbsoluteSensorRange = AbsoluteSensorRangeValue.Signed_PlusMinusHalf;
79+
canCoderConfig.MagnetSensor.SensorDirection = SensorDirectionValue.Clockwise_Positive;
80+
81+
for (int modIdx = 0; modIdx < m_modConfigs.length; modIdx++) {
82+
canCoderConfig.MagnetSensor.MagnetOffset =
83+
m_modConfigs[modIdx].m_canCoderOffset.getRotations();
84+
m_angleMotors[modIdx].getConfigurator().apply(angleMotorConfig);
85+
m_canCoders[modIdx].getConfigurator().apply(canCoderConfig);
86+
m_angleMotors[modIdx].setPosition(m_canCoders[modIdx].getPosition().refresh().getValue());
7187
}
72-
public static void periodic() {
73-
for (TalonFX F : motor) {
74-
PositionDutyCycle mRequest = new PositionDutyCycle(0);
75-
F.setControl(mRequest);
76-
}
88+
}
89+
90+
public static void periodic() {
91+
for (TalonFX angleMotor : m_angleMotors) {
92+
angleMotor.setControl(new MotionMagicExpoVoltage(0));
7793
}
94+
}
7895
}

‎src/main/java/frc/robot/Robot.java

+21-4
Original file line numberDiff line numberDiff line change
@@ -4,18 +4,22 @@
44

55
package frc.robot;
66

7-
import edu.wpi.first.wpilibj.TimedRobot;
7+
import com.ctre.phoenix6.SignalLogger;
88
import edu.wpi.first.wpilibj2.command.Command;
99
import edu.wpi.first.wpilibj2.command.CommandScheduler;
10-
import frc.robot.Interfaces.AngleMotorControl;
10+
import frc.robot.interfaces.AngleMotorControl;
11+
import org.littletonrobotics.junction.LoggedRobot;
12+
import org.littletonrobotics.junction.Logger;
13+
import org.littletonrobotics.junction.networktables.NT4Publisher;
14+
import org.littletonrobotics.junction.wpilog.WPILOGWriter;
1115

1216
/**
1317
* The VM is configured to automatically run this class, and to call the functions corresponding to
1418
* each mode, as described in the TimedRobot documentation. If you change the name of this class or
1519
* the package after creating this project, you must also update the build.gradle file in the
1620
* project.
1721
*/
18-
public class Robot extends TimedRobot {
22+
public class Robot extends LoggedRobot {
1923
private Command m_autonomousCommand;
2024

2125
private RobotContainer m_robotContainer;
@@ -26,6 +30,17 @@ public class Robot extends TimedRobot {
2630
*/
2731
@Override
2832
public void robotInit() {
33+
Logger.recordMetadata("ProjectName", "SysID"); // Set a metadata value
34+
35+
Logger.addDataReceiver(new WPILOGWriter()); // Log to a USB stick ("/U/logs")
36+
Logger.addDataReceiver(new NT4Publisher()); // Publish data to NetworkTables
37+
// new PowerDistribution(1, ModuleType.kRev); // Enables power distribution logging
38+
39+
// Logger.disableDeterministicTimestamps() // See "Deterministic Timestamps" in the
40+
// "Understanding Data Flow" page
41+
Logger.start(); // Start logging! No more data receivers, replay sources, or metadata values may
42+
// be added.
43+
2944
// Instantiate our RobotContainer. This will perform all our button bindings, and put our
3045
// autonomous chooser on the dashboard.
3146
m_robotContainer = new RobotContainer();
@@ -50,7 +65,9 @@ public void robotPeriodic() {
5065

5166
/** This function is called once each time the robot enters Disabled mode. */
5267
@Override
53-
public void disabledInit() {}
68+
public void disabledInit() {
69+
SignalLogger.stop();
70+
}
5471

5572
@Override
5673
public void disabledPeriodic() {}

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

+19-13
Original file line numberDiff line numberDiff line change
@@ -4,13 +4,12 @@
44

55
package frc.robot;
66

7-
import frc.robot.Constants.OperatorConstants;
8-
import frc.robot.commands.Autos;
9-
import frc.robot.commands.ExampleCommand;
10-
import frc.robot.subsystems.ExampleSubsystem;
117
import edu.wpi.first.wpilibj2.command.Command;
128
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
139
import edu.wpi.first.wpilibj2.command.button.Trigger;
10+
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine;
11+
import frc.robot.Constants.OperatorConstants;
12+
import frc.robot.subsystems.SysIdSubsystem;
1413

1514
/**
1615
* This class is where the bulk of the robot should be declared. Since Command-based is a
@@ -20,7 +19,7 @@
2019
*/
2120
public class RobotContainer {
2221
// The robot's subsystems and commands are defined here...
23-
private final ExampleSubsystem m_exampleSubsystem = new ExampleSubsystem();
22+
private final SysIdSubsystem m_sysIdSubsystem = new SysIdSubsystem();
2423

2524
// Replace with CommandPS4Controller or CommandJoystick if needed
2625
private final CommandXboxController m_driverController =
@@ -42,13 +41,20 @@ public RobotContainer() {
4241
* joysticks}.
4342
*/
4443
private void configureBindings() {
45-
// Schedule `ExampleCommand` when `exampleCondition` changes to `true`
46-
new Trigger(m_exampleSubsystem::exampleCondition)
47-
.onTrue(new ExampleCommand(m_exampleSubsystem));
48-
49-
// Schedule `exampleMethodCommand` when the Xbox controller's B button is pressed,
50-
// cancelling on release.
51-
m_driverController.b().whileTrue(m_exampleSubsystem.exampleMethodCommand());
44+
// Bind full set of SysId routine tests to buttons; a complete routine should run each of these
45+
// once.
46+
m_driverController
47+
.a()
48+
.whileTrue(m_sysIdSubsystem.sysIdQuasistatic(SysIdRoutine.Direction.kForward));
49+
m_driverController
50+
.b()
51+
.whileTrue(m_sysIdSubsystem.sysIdQuasistatic(SysIdRoutine.Direction.kReverse));
52+
m_driverController
53+
.x()
54+
.whileTrue(m_sysIdSubsystem.sysIdDynamic(SysIdRoutine.Direction.kForward));
55+
m_driverController
56+
.y()
57+
.whileTrue(m_sysIdSubsystem.sysIdDynamic(SysIdRoutine.Direction.kReverse));
5258
}
5359

5460
/**
@@ -58,6 +64,6 @@ private void configureBindings() {
5864
*/
5965
public Command getAutonomousCommand() {
6066
// An example command will be run in autonomous
61-
return Autos.exampleAuto(m_exampleSubsystem);
67+
return m_sysIdSubsystem.fullSysIdCommand();
6268
}
6369
}

‎src/main/java/frc/robot/commands/Autos.java

-20
This file was deleted.

‎src/main/java/frc/robot/commands/ExampleCommand.java

-43
This file was deleted.

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

-47
This file was deleted.
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,109 @@
1+
// Copyright (c) FIRST and other WPILib contributors.
2+
// Open Source Software; you can modify and/or share it under the terms of
3+
// the WPILib BSD license file in the root directory of this project.
4+
5+
package frc.robot.subsystems;
6+
7+
import static edu.wpi.first.units.Units.Second;
8+
import static edu.wpi.first.units.Units.Seconds;
9+
import static edu.wpi.first.units.Units.Volts;
10+
11+
import com.ctre.phoenix6.SignalLogger;
12+
import com.ctre.phoenix6.controls.Follower;
13+
import com.ctre.phoenix6.controls.VoltageOut;
14+
import com.ctre.phoenix6.hardware.TalonFX;
15+
import edu.wpi.first.units.Measure;
16+
import edu.wpi.first.units.Voltage;
17+
import edu.wpi.first.wpilibj2.command.Command;
18+
import edu.wpi.first.wpilibj2.command.SubsystemBase;
19+
import edu.wpi.first.wpilibj2.command.WaitCommand;
20+
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine;
21+
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine.Direction;
22+
import frc.lib.sysid.SysIdRoutinePhoenixConfig;
23+
24+
public class SysIdSubsystem extends SubsystemBase {
25+
26+
private final TalonFX m_motor0 = new TalonFX(0, "rio");
27+
private final TalonFX m_motor1 = new TalonFX(1, "rio");
28+
private final TalonFX m_motor2 = new TalonFX(2, "rio");
29+
private final TalonFX m_motor3 = new TalonFX(3, "rio");
30+
31+
// Create a new SysId routine for characterizing the drive.
32+
private final SysIdRoutine m_sysIdRoutine =
33+
new SysIdRoutine(
34+
SysIdRoutinePhoenixConfig.get(
35+
Volts.per(Second).of(1.0), Volts.of(7.0), Seconds.of(10.0), this.getName()),
36+
new SysIdRoutine.Mechanism(
37+
// Tell SysId how to plumb the driving voltage to the motors.
38+
(Measure<Voltage> volts) -> {
39+
m_motor0.setControl(new VoltageOut(volts.in(Volts)));
40+
},
41+
// Phoenix 6 will log all the necessary status signals by default.
42+
// No need to define a log routine
43+
log -> {},
44+
// Tell SysId to make generated commands require this subsystem, suffix test state in
45+
// WPILog with this subsystem's name ("drive")
46+
this));
47+
48+
/** Creates a new Drive subsystem. */
49+
public SysIdSubsystem() {
50+
m_motor1.setControl(new Follower(m_motor0.getDeviceID(), false));
51+
m_motor2.setControl(new Follower(m_motor0.getDeviceID(), false));
52+
m_motor3.setControl(new Follower(m_motor0.getDeviceID(), false));
53+
// Setting the update frequency of the signals will determine the log file resolution
54+
configureStatusSignals(m_motor0, 1000.0);
55+
configureStatusSignals(m_motor1, 1000.0);
56+
configureStatusSignals(m_motor2, 1000.0);
57+
configureStatusSignals(m_motor3, 1000.0);
58+
}
59+
60+
/**
61+
* Configure the Status Signals required for SysId of the motor to have the given logging rate.
62+
*
63+
* @param motor The {@link TalonFX} motor for which to configure the status signals
64+
* @param frequencyHz The desired logging frequency of the signals in Hz
65+
*/
66+
private void configureStatusSignals(TalonFX motor, double frequencyHz) {
67+
motor.getMotorVoltage().setUpdateFrequency(frequencyHz);
68+
motor.getPosition().setUpdateFrequency(frequencyHz);
69+
motor.getVelocity().setUpdateFrequency(frequencyHz);
70+
motor.optimizeBusUtilization();
71+
}
72+
73+
/**
74+
* Returns a command that will execute a quasistatic test in the given direction.
75+
*
76+
* @param direction The direction (forward or reverse) to run the test in
77+
*/
78+
public Command sysIdQuasistatic(SysIdRoutine.Direction direction) {
79+
return m_sysIdRoutine.quasistatic(direction);
80+
}
81+
82+
/**
83+
* Returns a command that will execute a dynamic test in the given direction.
84+
*
85+
* @param direction The direction (forward or reverse) to run the test in
86+
*/
87+
public Command sysIdDynamic(SysIdRoutine.Direction direction) {
88+
return m_sysIdRoutine.dynamic(direction);
89+
}
90+
91+
/** Returns the full SysId Command Sequence */
92+
public Command fullSysIdCommand() {
93+
return runOnce(
94+
() -> {
95+
SignalLogger.start();
96+
})
97+
.andThen(this.sysIdQuasistatic(Direction.kForward))
98+
.andThen(new WaitCommand(3))
99+
.andThen(this.sysIdQuasistatic(Direction.kReverse))
100+
.andThen(new WaitCommand(3))
101+
.andThen(this.sysIdDynamic(Direction.kForward))
102+
.andThen(new WaitCommand(3))
103+
.andThen(this.sysIdDynamic(Direction.kReverse))
104+
.andThen(
105+
() -> {
106+
SignalLogger.stop();
107+
});
108+
}
109+
}

‎vendordeps/AdvantageKit.json

+42
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,42 @@
1+
{
2+
"fileName": "AdvantageKit.json",
3+
"name": "AdvantageKit",
4+
"version": "3.0.2",
5+
"uuid": "d820cc26-74e3-11ec-90d6-0242ac120003",
6+
"frcYear": "2024",
7+
"mavenUrls": [],
8+
"jsonUrl": "https://github.com/Mechanical-Advantage/AdvantageKit/releases/latest/download/AdvantageKit.json",
9+
"javaDependencies": [
10+
{
11+
"groupId": "org.littletonrobotics.akit.junction",
12+
"artifactId": "wpilib-shim",
13+
"version": "3.0.2"
14+
},
15+
{
16+
"groupId": "org.littletonrobotics.akit.junction",
17+
"artifactId": "junction-core",
18+
"version": "3.0.2"
19+
},
20+
{
21+
"groupId": "org.littletonrobotics.akit.conduit",
22+
"artifactId": "conduit-api",
23+
"version": "3.0.2"
24+
}
25+
],
26+
"jniDependencies": [
27+
{
28+
"groupId": "org.littletonrobotics.akit.conduit",
29+
"artifactId": "conduit-wpilibio",
30+
"version": "3.0.2",
31+
"skipInvalidPlatforms": false,
32+
"isJar": false,
33+
"validPlatforms": [
34+
"linuxathena",
35+
"windowsx86-64",
36+
"linuxx86-64",
37+
"osxuniversal"
38+
]
39+
}
40+
],
41+
"cppDependencies": []
42+
}

‎vendordeps/Phoenix6.json

+24-24
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
{
22
"fileName": "Phoenix6.json",
33
"name": "CTRE-Phoenix (v6)",
4-
"version": "24.1.0",
4+
"version": "24.2.0",
55
"frcYear": 2024,
66
"uuid": "e995de00-2c64-4df5-8831-c1441420ff19",
77
"mavenUrls": [
@@ -19,14 +19,14 @@
1919
{
2020
"groupId": "com.ctre.phoenix6",
2121
"artifactId": "wpiapi-java",
22-
"version": "24.1.0"
22+
"version": "24.2.0"
2323
}
2424
],
2525
"jniDependencies": [
2626
{
2727
"groupId": "com.ctre.phoenix6",
2828
"artifactId": "tools",
29-
"version": "24.1.0",
29+
"version": "24.2.0",
3030
"isJar": false,
3131
"skipInvalidPlatforms": true,
3232
"validPlatforms": [
@@ -39,7 +39,7 @@
3939
{
4040
"groupId": "com.ctre.phoenix6.sim",
4141
"artifactId": "tools-sim",
42-
"version": "24.1.0",
42+
"version": "24.2.0",
4343
"isJar": false,
4444
"skipInvalidPlatforms": true,
4545
"validPlatforms": [
@@ -52,7 +52,7 @@
5252
{
5353
"groupId": "com.ctre.phoenix6.sim",
5454
"artifactId": "simTalonSRX",
55-
"version": "24.1.0",
55+
"version": "24.2.0",
5656
"isJar": false,
5757
"skipInvalidPlatforms": true,
5858
"validPlatforms": [
@@ -65,7 +65,7 @@
6565
{
6666
"groupId": "com.ctre.phoenix6.sim",
6767
"artifactId": "simTalonFX",
68-
"version": "24.1.0",
68+
"version": "24.2.0",
6969
"isJar": false,
7070
"skipInvalidPlatforms": true,
7171
"validPlatforms": [
@@ -78,7 +78,7 @@
7878
{
7979
"groupId": "com.ctre.phoenix6.sim",
8080
"artifactId": "simVictorSPX",
81-
"version": "24.1.0",
81+
"version": "24.2.0",
8282
"isJar": false,
8383
"skipInvalidPlatforms": true,
8484
"validPlatforms": [
@@ -91,7 +91,7 @@
9191
{
9292
"groupId": "com.ctre.phoenix6.sim",
9393
"artifactId": "simPigeonIMU",
94-
"version": "24.1.0",
94+
"version": "24.2.0",
9595
"isJar": false,
9696
"skipInvalidPlatforms": true,
9797
"validPlatforms": [
@@ -104,7 +104,7 @@
104104
{
105105
"groupId": "com.ctre.phoenix6.sim",
106106
"artifactId": "simCANCoder",
107-
"version": "24.1.0",
107+
"version": "24.2.0",
108108
"isJar": false,
109109
"skipInvalidPlatforms": true,
110110
"validPlatforms": [
@@ -117,7 +117,7 @@
117117
{
118118
"groupId": "com.ctre.phoenix6.sim",
119119
"artifactId": "simProTalonFX",
120-
"version": "24.1.0",
120+
"version": "24.2.0",
121121
"isJar": false,
122122
"skipInvalidPlatforms": true,
123123
"validPlatforms": [
@@ -130,7 +130,7 @@
130130
{
131131
"groupId": "com.ctre.phoenix6.sim",
132132
"artifactId": "simProCANcoder",
133-
"version": "24.1.0",
133+
"version": "24.2.0",
134134
"isJar": false,
135135
"skipInvalidPlatforms": true,
136136
"validPlatforms": [
@@ -143,7 +143,7 @@
143143
{
144144
"groupId": "com.ctre.phoenix6.sim",
145145
"artifactId": "simProPigeon2",
146-
"version": "24.1.0",
146+
"version": "24.2.0",
147147
"isJar": false,
148148
"skipInvalidPlatforms": true,
149149
"validPlatforms": [
@@ -158,7 +158,7 @@
158158
{
159159
"groupId": "com.ctre.phoenix6",
160160
"artifactId": "wpiapi-cpp",
161-
"version": "24.1.0",
161+
"version": "24.2.0",
162162
"libName": "CTRE_Phoenix6_WPI",
163163
"headerClassifier": "headers",
164164
"sharedLibrary": true,
@@ -173,7 +173,7 @@
173173
{
174174
"groupId": "com.ctre.phoenix6",
175175
"artifactId": "tools",
176-
"version": "24.1.0",
176+
"version": "24.2.0",
177177
"libName": "CTRE_PhoenixTools",
178178
"headerClassifier": "headers",
179179
"sharedLibrary": true,
@@ -188,7 +188,7 @@
188188
{
189189
"groupId": "com.ctre.phoenix6.sim",
190190
"artifactId": "wpiapi-cpp-sim",
191-
"version": "24.1.0",
191+
"version": "24.2.0",
192192
"libName": "CTRE_Phoenix6_WPISim",
193193
"headerClassifier": "headers",
194194
"sharedLibrary": true,
@@ -203,7 +203,7 @@
203203
{
204204
"groupId": "com.ctre.phoenix6.sim",
205205
"artifactId": "tools-sim",
206-
"version": "24.1.0",
206+
"version": "24.2.0",
207207
"libName": "CTRE_PhoenixTools_Sim",
208208
"headerClassifier": "headers",
209209
"sharedLibrary": true,
@@ -218,7 +218,7 @@
218218
{
219219
"groupId": "com.ctre.phoenix6.sim",
220220
"artifactId": "simTalonSRX",
221-
"version": "24.1.0",
221+
"version": "24.2.0",
222222
"libName": "CTRE_SimTalonSRX",
223223
"headerClassifier": "headers",
224224
"sharedLibrary": true,
@@ -233,7 +233,7 @@
233233
{
234234
"groupId": "com.ctre.phoenix6.sim",
235235
"artifactId": "simTalonFX",
236-
"version": "24.1.0",
236+
"version": "24.2.0",
237237
"libName": "CTRE_SimTalonFX",
238238
"headerClassifier": "headers",
239239
"sharedLibrary": true,
@@ -248,7 +248,7 @@
248248
{
249249
"groupId": "com.ctre.phoenix6.sim",
250250
"artifactId": "simVictorSPX",
251-
"version": "24.1.0",
251+
"version": "24.2.0",
252252
"libName": "CTRE_SimVictorSPX",
253253
"headerClassifier": "headers",
254254
"sharedLibrary": true,
@@ -263,7 +263,7 @@
263263
{
264264
"groupId": "com.ctre.phoenix6.sim",
265265
"artifactId": "simPigeonIMU",
266-
"version": "24.1.0",
266+
"version": "24.2.0",
267267
"libName": "CTRE_SimPigeonIMU",
268268
"headerClassifier": "headers",
269269
"sharedLibrary": true,
@@ -278,7 +278,7 @@
278278
{
279279
"groupId": "com.ctre.phoenix6.sim",
280280
"artifactId": "simCANCoder",
281-
"version": "24.1.0",
281+
"version": "24.2.0",
282282
"libName": "CTRE_SimCANCoder",
283283
"headerClassifier": "headers",
284284
"sharedLibrary": true,
@@ -293,7 +293,7 @@
293293
{
294294
"groupId": "com.ctre.phoenix6.sim",
295295
"artifactId": "simProTalonFX",
296-
"version": "24.1.0",
296+
"version": "24.2.0",
297297
"libName": "CTRE_SimProTalonFX",
298298
"headerClassifier": "headers",
299299
"sharedLibrary": true,
@@ -308,7 +308,7 @@
308308
{
309309
"groupId": "com.ctre.phoenix6.sim",
310310
"artifactId": "simProCANcoder",
311-
"version": "24.1.0",
311+
"version": "24.2.0",
312312
"libName": "CTRE_SimProCANcoder",
313313
"headerClassifier": "headers",
314314
"sharedLibrary": true,
@@ -323,7 +323,7 @@
323323
{
324324
"groupId": "com.ctre.phoenix6.sim",
325325
"artifactId": "simProPigeon2",
326-
"version": "24.1.0",
326+
"version": "24.2.0",
327327
"libName": "CTRE_SimProPigeon2",
328328
"headerClassifier": "headers",
329329
"sharedLibrary": true,

0 commit comments

Comments
 (0)
Please sign in to comment.