Skip to content
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ import edu.wpi.first.gradlerio.deploy.roborio.RoboRIO
*/

plugins {
id "edu.wpi.first.GradleRIO" version "2025.3.1"
id "edu.wpi.first.GradleRIO" version "2026.1.1-beta-1"
id 'scala'
id 'checkstyle'
id 'jacoco'
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/xbot/common/command/BaseRobot.java
Original file line number Diff line number Diff line change
Expand Up @@ -210,7 +210,7 @@ public void autonomousInit() {
this.autonomousCommand = this.autonomousCommandSelector.getCurrentAutonomousCommand();
if(this.autonomousCommand != null) {
log.info("Starting autonomous command: " + this.autonomousCommand);
this.autonomousCommand.schedule();
CommandScheduler.getInstance().schedule(this.autonomousCommand);
} else {
log.warn("No autonomous command set.");
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -136,7 +136,7 @@ public void setTrapezoidalProfileJerk(Velocity<AngularAccelerationUnit> jerk) {
@Override
public void setTrapezoidalProfileMaxVelocity(AngularVelocity velocity) {
var config = new SparkMaxConfig();
config.closedLoop.maxMotion.maxVelocity(velocity.in(RPM));
config.closedLoop.maxMotion.cruiseVelocity(velocity.in(RPM));
this.internalSparkMax.configure(config,
SparkBase.ResetMode.kNoResetSafeParameters,
SparkBase.PersistMode.kNoPersistParameters);
Expand All @@ -152,8 +152,8 @@ public void setPidDirectly(double p, double i, double d, double velocityFF, doub
config.closedLoop
.p(p, getClosedLoopSlot(slot))
.i(i, getClosedLoopSlot(slot))
.d(d, getClosedLoopSlot(slot))
.velocityFF(velocityFF, getClosedLoopSlot(slot));
.d(d, getClosedLoopSlot(slot));
config.closedLoop.feedForward.kV(velocityFF, getClosedLoopSlot(slot));
this.internalSparkMax.configure(config,
SparkBase.ResetMode.kNoResetSafeParameters,
SparkBase.PersistMode.kNoPersistParameters);
Expand Down Expand Up @@ -213,7 +213,7 @@ public void setRawPositionTarget(Angle rawPosition, MotorPidMode mode, int slot)
}
this.internalSparkMax
.getClosedLoopController()
.setReference(rawPosition.in(Rotations), controlType, getClosedLoopSlot(slot));
.setSetpoint(rawPosition.in(Rotations), controlType, getClosedLoopSlot(slot));
}

public AngularVelocity getRawVelocity_internal() {
Expand All @@ -233,7 +233,7 @@ public void setRawVelocityTarget(AngularVelocity rawVelocity, MotorPidMode mode,
}
this.internalSparkMax
.getClosedLoopController()
.setReference(rawVelocity.in(RPM), controlType, getClosedLoopSlot(slot));
.setSetpoint(rawVelocity.in(RPM), controlType, getClosedLoopSlot(slot));
}

@Override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,7 @@ public CANTalonFxWpiAdapter(
@Assisted("defaultPIDProperties") XCANMotorControllerPIDProperties defaultPIDProperties
) {
super(info, owningSystemPrefix, propertyFactory, police, pidPropertyPrefix, defaultPIDProperties);
this.internalTalonFx = new TalonFX(info.deviceId(), info.busId().id());
this.internalTalonFx = new TalonFX(info.deviceId(), info.busId().toPhoenixCANBus());

this.rotorPositionSignal = this.internalTalonFx.getRotorPosition(false);
this.rotorVelocitySignal = this.internalTalonFx.getRotorVelocity(false);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ public CANCoderAdapter(@Assisted("deviceInfo") DeviceInfo deviceInfo,
this.inverted = deviceInfo.inverted;
this.magnetOffset = 0.0;

this.cancoder = new CANcoder(deviceInfo.channel, deviceInfo.canBusId.id());
this.cancoder = new CANcoder(deviceInfo.channel, deviceInfo.canBusId.toPhoenixCANBus());

var currentConfig = getCurrentConfiguration();
currentConfig.MagnetSensor.AbsoluteSensorDiscontinuityPoint = 0.5;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ public abstract static class Pigeon2AdapterFactory extends XGyroFactory {
@AssistedInject
public Pigeon2Adapter(DevicePolice police, @Assisted IMUInfo imuInfo) {
super(imuInfo);
this.pigeon = new Pigeon2(imuInfo.deviceId(), imuInfo.canBusId().id());
this.pigeon = new Pigeon2(imuInfo.deviceId(), imuInfo.canBusId().toPhoenixCANBus());
police.registerDevice(DevicePolice.DeviceType.CAN, imuInfo.canBusId(), imuInfo.deviceId(), this);

this.yawSignal = pigeon.getYaw();
Expand Down
Original file line number Diff line number Diff line change
@@ -1,10 +1,30 @@
package xbot.common.injection.electrical_contract;

import com.ctre.phoenix6.CANBus;
import scala.util.hashing.Hashing;

/**
* Represents a CAN bus ID
* @param id Bus name string
*/
public record CANBusId(String id) {
public static final CANBusId RIO = new CANBusId("rio");
public static final CANBusId DefaultCanivore = new CANBusId("*");

private static final CANBus DefaultPhoenixRio = CANBus.roboRIO();
private static final CANBus DefaultPhoenixCanivore = new CANBus("*");

/**
* Converts this CANBusId to a Phoenix CANBus object.
* @return Corresponding CANBus object
*/
public CANBus toPhoenixCANBus() {
if (this.equals(RIO)) {
return DefaultPhoenixRio;
} else if (this.equals(DefaultCanivore)) {
return DefaultPhoenixCanivore;
} else {
throw new IllegalArgumentException("Unknown CAN bus ID: " + this.id);
}
}
}
2 changes: 1 addition & 1 deletion vendordeps/AdvantageKit.json
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
"name": "AdvantageKit",
"version": "4.0.0",
"uuid": "d820cc26-74e3-11ec-90d6-0242ac120003",
"frcYear": "2025",
"frcYear": "2026beta",
"mavenUrls": [
"https://frcmaven.wpi.edu/artifactory/littletonrobotics-mvn-release/"
],
Expand Down
2 changes: 1 addition & 1 deletion vendordeps/LaserCAN.json
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
"fileName": "libgrapplefrc2025.json",
"name": "libgrapplefrc",
"version": "2025.1.0",
"frcYear": "2025",
"frcYear": "2026beta",
"uuid": "8ef3423d-9532-4665-8339-206dae1d7168",
"mavenUrls": [ "https://storage.googleapis.com/grapple-frc-maven" ],
"jsonUrl": "https://storage.googleapis.com/grapple-frc-maven/libgrapplefrc2025.json",
Expand Down
2 changes: 1 addition & 1 deletion vendordeps/NavX.json
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
"name": "Studica",
"version": "2025.0.0",
"uuid": "cb311d09-36e9-4143-a032-55bb2b94443b",
"frcYear": "2025",
"frcYear": "2026beta",
"mavenUrls": [
"https://dev.studica.com/maven/release/2025/"
],
Expand Down
2 changes: 1 addition & 1 deletion vendordeps/PathplannerLib.json
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
"name": "PathplannerLib",
"version": "2025.1.1",
"uuid": "1b42324f-17c6-4875-8e77-1c312bc8c786",
"frcYear": "2025",
"frcYear": "2026beta",
"mavenUrls": [
"https://3015rangerrobotics.github.io/pathplannerlib/repo"
],
Expand Down
36 changes: 18 additions & 18 deletions vendordeps/Phoenix5.json
Original file line number Diff line number Diff line change
@@ -1,50 +1,50 @@
{
"fileName": "Phoenix5-frc2025-latest.json",
"fileName": "Phoenix5-frc2026-beta-latest.json",
"name": "CTRE-Phoenix (v5)",
"version": "5.35.1",
"frcYear": "2025",
"version": "5.36.0-beta-1",
"frcYear": "2026beta",
"uuid": "ab676553-b602-441f-a38d-f1296eff6537",
"mavenUrls": [
"https://maven.ctr-electronics.com/release/"
],
"jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix/Phoenix5-frc2025-latest.json",
"jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix/Phoenix5-frc2026-beta-latest.json",
"requires": [
{
"uuid": "e995de00-2c64-4df5-8831-c1441420ff19",
"errorMessage": "Phoenix 5 requires low-level libraries from Phoenix 6. Please add the Phoenix 6 vendordep before adding Phoenix 5.",
"offlineFileName": "Phoenix6-frc2025-latest.json",
"onlineUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2025-latest.json"
"offlineFileName": "Phoenix6-frc2026-beta-latest.json",
"onlineUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2026-beta-latest.json"
}
],
"conflictsWith": [
{
"uuid": "e7900d8d-826f-4dca-a1ff-182f658e98af",
"errorMessage": "Users must use the Phoenix 5 replay vendordep when using the Phoenix 6 replay vendordep.",
"offlineFileName": "Phoenix6-replay-frc2025-latest.json"
"offlineFileName": "Phoenix6-replay-frc2026-beta-latest.json"
},
{
"uuid": "fbc886a4-2cec-40c0-9835-71086a8cc3df",
"errorMessage": "Users cannot have both the replay and regular Phoenix 5 vendordeps in their robot program.",
"offlineFileName": "Phoenix5-replay-frc2025-latest.json"
"offlineFileName": "Phoenix5-replay-frc2026-beta-latest.json"
}
],
"javaDependencies": [
{
"groupId": "com.ctre.phoenix",
"artifactId": "api-java",
"version": "5.35.1"
"version": "5.36.0-beta-1"
},
{
"groupId": "com.ctre.phoenix",
"artifactId": "wpiapi-java",
"version": "5.35.1"
"version": "5.36.0-beta-1"
}
],
"jniDependencies": [
{
"groupId": "com.ctre.phoenix",
"artifactId": "cci",
"version": "5.35.1",
"version": "5.36.0-beta-1",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
Expand All @@ -58,7 +58,7 @@
{
"groupId": "com.ctre.phoenix.sim",
"artifactId": "cci-sim",
"version": "5.35.1",
"version": "5.36.0-beta-1",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
Expand All @@ -74,7 +74,7 @@
{
"groupId": "com.ctre.phoenix",
"artifactId": "wpiapi-cpp",
"version": "5.35.1",
"version": "5.36.0-beta-1",
"libName": "CTRE_Phoenix_WPI",
"headerClassifier": "headers",
"sharedLibrary": true,
Expand All @@ -90,7 +90,7 @@
{
"groupId": "com.ctre.phoenix",
"artifactId": "api-cpp",
"version": "5.35.1",
"version": "5.36.0-beta-1",
"libName": "CTRE_Phoenix",
"headerClassifier": "headers",
"sharedLibrary": true,
Expand All @@ -106,7 +106,7 @@
{
"groupId": "com.ctre.phoenix",
"artifactId": "cci",
"version": "5.35.1",
"version": "5.36.0-beta-1",
"libName": "CTRE_PhoenixCCI",
"headerClassifier": "headers",
"sharedLibrary": true,
Expand All @@ -122,7 +122,7 @@
{
"groupId": "com.ctre.phoenix.sim",
"artifactId": "wpiapi-cpp-sim",
"version": "5.35.1",
"version": "5.36.0-beta-1",
"libName": "CTRE_Phoenix_WPISim",
"headerClassifier": "headers",
"sharedLibrary": true,
Expand All @@ -138,7 +138,7 @@
{
"groupId": "com.ctre.phoenix.sim",
"artifactId": "api-cpp-sim",
"version": "5.35.1",
"version": "5.36.0-beta-1",
"libName": "CTRE_PhoenixSim",
"headerClassifier": "headers",
"sharedLibrary": true,
Expand All @@ -154,7 +154,7 @@
{
"groupId": "com.ctre.phoenix.sim",
"artifactId": "cci-sim",
"version": "5.35.1",
"version": "5.36.0-beta-1",
"libName": "CTRE_PhoenixCCISim",
"headerClassifier": "headers",
"sharedLibrary": true,
Expand Down
Loading