Skip to content

Commit

Permalink
Update vendor libraries
Browse files Browse the repository at this point in the history
Set module configs constants for compbot
  • Loading branch information
suryatho committed Feb 18, 2024
1 parent 125745d commit 9b4d5f1
Show file tree
Hide file tree
Showing 9 changed files with 76 additions and 53 deletions.
2 changes: 1 addition & 1 deletion src/main/java/org/littletonrobotics/frc2024/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@
*/
public final class Constants {
public static final double loopPeriodSecs = 0.02;
private static RobotType robotType = RobotType.DEVBOT;
private static RobotType robotType = RobotType.COMPBOT;
public static final boolean tuningMode = true;

public static RobotType getRobot() {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -88,7 +88,13 @@ public RobotContainer() {
if (Constants.getMode() != Constants.Mode.REPLAY) {
switch (Constants.getRobot()) {
case COMPBOT -> {
// No impl yet
drive =
new Drive(
new GyroIOPigeon2(true),
new ModuleIOKrakenFOC(DriveConstants.moduleConfigs[0]),
new ModuleIOKrakenFOC(DriveConstants.moduleConfigs[1]),
new ModuleIOKrakenFOC(DriveConstants.moduleConfigs[2]),
new ModuleIOKrakenFOC(DriveConstants.moduleConfigs[3]));
}
case DEVBOT -> {
drive =
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,14 @@ public final class DriveConstants {
// Module Constants
public static ModuleConfig[] moduleConfigs =
switch (Constants.getRobot()) {
case COMPBOT, DEVBOT ->
case COMPBOT ->
new ModuleConfig[] {
new ModuleConfig(16, 12, 0, new Rotation2d(-1.93585), true),
new ModuleConfig(19, 14, 1, new Rotation2d(0.73053), true),
new ModuleConfig(17, 13, 2, new Rotation2d(-0.50507), true),
new ModuleConfig(18, 15, 3, new Rotation2d(-1.51666), true)
};
case DEVBOT ->
new ModuleConfig[] {
new ModuleConfig(15, 11, 0, new Rotation2d(-0.036), true),
new ModuleConfig(12, 9, 1, new Rotation2d(1.0185), true),
Expand All @@ -86,12 +93,12 @@ public final class DriveConstants {
switch (Constants.getRobot()) {
case COMPBOT ->
new ModuleConstants(
2.0,
0.0,
200.0,
0.0,
200.0,
20.0,
0.0,
0.0,
0.0,
0.0,
Mk4iReductions.L3.reduction,
Mk4iReductions.TURN.reduction);
case DEVBOT ->
Expand Down Expand Up @@ -125,7 +132,8 @@ public final class DriveConstants {
// Trajectory Following
public static TrajectoryConstants trajectoryConstants =
switch (Constants.getRobot()) {
case COMPBOT, DEVBOT ->
case COMPBOT -> new TrajectoryConstants(0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0);
case DEVBOT ->
new TrajectoryConstants(
6.0,
0.0,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,12 +18,18 @@

/** IO implementation for Pigeon2 */
public class GyroIOPigeon2 implements GyroIO {
private final Pigeon2 pigeon = new Pigeon2(0);
private final StatusSignal<Double> yaw = pigeon.getYaw();
private static final int id = 0;

private final Pigeon2 pigeon;
private final StatusSignal<Double> yaw;
private final Queue<Double> yawPositionQueue;
private final StatusSignal<Double> yawVelocity = pigeon.getAngularVelocityZWorld();
private final StatusSignal<Double> yawVelocity;

public GyroIOPigeon2(boolean phoenixDrive) {
pigeon = new Pigeon2(id, "canivore");
yaw = pigeon.getYaw();
yawVelocity = pigeon.getAngularVelocityZWorld();

pigeon.getConfigurator().apply(new Pigeon2Configuration());
pigeon.getConfigurator().setYaw(0.0);
yaw.setUpdateFrequency(DriveConstants.odometryFrequency);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ public Module(ModuleIO io, int index) {
/** Called while blocking odometry thread */
public void updateInputs() {
io.updateInputs(inputs);
Logger.processInputs("Drive/" + moduleNames[index] + "_Module", inputs);
Logger.processInputs("Drive/Module" + index, inputs);

// Update ff and controllers
LoggedTunableNumber.ifChanged(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -104,6 +104,15 @@ public ModuleIOKrakenFOC(ModuleConfig config) {
if (!error) break;
}

// 250hz signals
drivePosition = driveTalon.getPosition();
turnPosition = turnTalon.getPosition();
BaseStatusSignal.setUpdateFrequencyForAll(odometryFrequency, drivePosition, turnPosition);

drivePositionQueue =
PhoenixOdometryThread.getInstance().registerSignal(driveTalon, drivePosition);
turnPositionQueue = PhoenixOdometryThread.getInstance().registerSignal(turnTalon, turnPosition);

// Get signals and set update rate
// 100hz signals
driveVelocity = driveTalon.getVelocity();
Expand Down Expand Up @@ -133,17 +142,11 @@ public ModuleIOKrakenFOC(ModuleConfig config) {
turnSupplyCurrent,
turnTorqueCurrent);

// 250hz signals
drivePosition = driveTalon.getPosition();
turnPosition = turnTalon.getPosition();
BaseStatusSignal.setUpdateFrequencyForAll(odometryFrequency, drivePosition, turnPosition);
drivePositionQueue =
PhoenixOdometryThread.getInstance().registerSignal(driveTalon, driveTalon.getPosition());
turnPositionQueue =
PhoenixOdometryThread.getInstance().registerSignal(turnTalon, turnTalon.getPosition());

// Reset turn position to absolute encoder position
turnTalon.setPosition(turnAbsolutePosition.get().getRotations());
turnTalon.setPosition(turnAbsolutePosition.get().getRotations(), 1.0);

driveTalon.optimizeBusUtilization(1.0);
turnTalon.optimizeBusUtilization(1.0);
}

@Override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,14 +12,14 @@
public class FlywheelConstants {
public static FlywheelConfig flywheelConfig =
switch (Constants.getRobot()) {
case COMPBOT -> null;
case COMPBOT -> new FlywheelConfig(0, 0, 0, 0, 0);
case DEVBOT -> new FlywheelConfig(5, 4, (1.0 / 2.0), 6000.0, 100.0);
case SIMBOT -> new FlywheelConfig(0, 0, (1.0 / 2.0), 6000.0, 50.0);
};

public static Gains gains =
switch (Constants.getRobot()) {
case COMPBOT -> null;
case COMPBOT -> new Gains(0, 0, 0, 0, 0, 0);
case DEVBOT -> new Gains(0.0006, 0.0, 0.05, 0.33329, 0.00083, 0.0);
case SIMBOT -> new Gains(0.05, 0.0, 0.0, 0.01, 0.00103, 0.0);
};
Expand Down
48 changes: 24 additions & 24 deletions vendordeps/Phoenix6.json
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
{
"fileName": "Phoenix6.json",
"name": "CTRE-Phoenix (v6)",
"version": "24.1.0",
"version": "24.2.0",
"frcYear": 2024,
"uuid": "e995de00-2c64-4df5-8831-c1441420ff19",
"mavenUrls": [
Expand All @@ -19,14 +19,14 @@
{
"groupId": "com.ctre.phoenix6",
"artifactId": "wpiapi-java",
"version": "24.1.0"
"version": "24.2.0"
}
],
"jniDependencies": [
{
"groupId": "com.ctre.phoenix6",
"artifactId": "tools",
"version": "24.1.0",
"version": "24.2.0",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
Expand All @@ -39,7 +39,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "tools-sim",
"version": "24.1.0",
"version": "24.2.0",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
Expand All @@ -52,7 +52,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simTalonSRX",
"version": "24.1.0",
"version": "24.2.0",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
Expand All @@ -65,7 +65,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simTalonFX",
"version": "24.1.0",
"version": "24.2.0",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
Expand All @@ -78,7 +78,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simVictorSPX",
"version": "24.1.0",
"version": "24.2.0",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
Expand All @@ -91,7 +91,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simPigeonIMU",
"version": "24.1.0",
"version": "24.2.0",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
Expand All @@ -104,7 +104,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simCANCoder",
"version": "24.1.0",
"version": "24.2.0",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
Expand All @@ -117,7 +117,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProTalonFX",
"version": "24.1.0",
"version": "24.2.0",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
Expand All @@ -130,7 +130,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProCANcoder",
"version": "24.1.0",
"version": "24.2.0",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
Expand All @@ -143,7 +143,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProPigeon2",
"version": "24.1.0",
"version": "24.2.0",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
Expand All @@ -158,7 +158,7 @@
{
"groupId": "com.ctre.phoenix6",
"artifactId": "wpiapi-cpp",
"version": "24.1.0",
"version": "24.2.0",
"libName": "CTRE_Phoenix6_WPI",
"headerClassifier": "headers",
"sharedLibrary": true,
Expand All @@ -173,7 +173,7 @@
{
"groupId": "com.ctre.phoenix6",
"artifactId": "tools",
"version": "24.1.0",
"version": "24.2.0",
"libName": "CTRE_PhoenixTools",
"headerClassifier": "headers",
"sharedLibrary": true,
Expand All @@ -188,7 +188,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "wpiapi-cpp-sim",
"version": "24.1.0",
"version": "24.2.0",
"libName": "CTRE_Phoenix6_WPISim",
"headerClassifier": "headers",
"sharedLibrary": true,
Expand All @@ -203,7 +203,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "tools-sim",
"version": "24.1.0",
"version": "24.2.0",
"libName": "CTRE_PhoenixTools_Sim",
"headerClassifier": "headers",
"sharedLibrary": true,
Expand All @@ -218,7 +218,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simTalonSRX",
"version": "24.1.0",
"version": "24.2.0",
"libName": "CTRE_SimTalonSRX",
"headerClassifier": "headers",
"sharedLibrary": true,
Expand All @@ -233,7 +233,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simTalonFX",
"version": "24.1.0",
"version": "24.2.0",
"libName": "CTRE_SimTalonFX",
"headerClassifier": "headers",
"sharedLibrary": true,
Expand All @@ -248,7 +248,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simVictorSPX",
"version": "24.1.0",
"version": "24.2.0",
"libName": "CTRE_SimVictorSPX",
"headerClassifier": "headers",
"sharedLibrary": true,
Expand All @@ -263,7 +263,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simPigeonIMU",
"version": "24.1.0",
"version": "24.2.0",
"libName": "CTRE_SimPigeonIMU",
"headerClassifier": "headers",
"sharedLibrary": true,
Expand All @@ -278,7 +278,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simCANCoder",
"version": "24.1.0",
"version": "24.2.0",
"libName": "CTRE_SimCANCoder",
"headerClassifier": "headers",
"sharedLibrary": true,
Expand All @@ -293,7 +293,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProTalonFX",
"version": "24.1.0",
"version": "24.2.0",
"libName": "CTRE_SimProTalonFX",
"headerClassifier": "headers",
"sharedLibrary": true,
Expand All @@ -308,7 +308,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProCANcoder",
"version": "24.1.0",
"version": "24.2.0",
"libName": "CTRE_SimProCANcoder",
"headerClassifier": "headers",
"sharedLibrary": true,
Expand All @@ -323,7 +323,7 @@
{
"groupId": "com.ctre.phoenix6.sim",
"artifactId": "simProPigeon2",
"version": "24.1.0",
"version": "24.2.0",
"libName": "CTRE_SimProPigeon2",
"headerClassifier": "headers",
"sharedLibrary": true,
Expand Down
Loading

0 comments on commit 9b4d5f1

Please sign in to comment.