Skip to content
This repository has been archived by the owner on Jan 13, 2025. It is now read-only.

update CTRE, Rev, Kauai vendordeps #7

Merged
merged 1 commit into from
Jan 15, 2024
Merged
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
89 changes: 45 additions & 44 deletions src/main/java/com/team766/hal/wpilib/NavXGyro.java
Original file line number Diff line number Diff line change
Expand Up @@ -8,48 +8,49 @@
import edu.wpi.first.wpilibj.I2C;

public class NavXGyro implements GyroReader {
private AHRS m_gyro;

public NavXGyro(final I2C.Port port) {
m_gyro = new AHRS(port);
// NOTE: It takes a bit of time until the gyro reader thread updates
// the connected status, so we can't check it immediately.
// TODO: Replace this with a status indicator
/*if (!m_gyro.isConnected()) {
Logger.get(Category.HAL).logData(Severity.ERROR, "NavX Gyro is not connected!");
} else {
Logger.get(Category.HAL).logData(Severity.INFO, "NavX Gyro is connected");
}*/
}

@Override
public void calibrate() {
m_gyro.calibrate();
}

@Override
public void reset() {
m_gyro.reset();
}

@Override
public double getAngle() {
return m_gyro.getAngle();
}

@Override
public double getRate() {
return m_gyro.getRate();
}

@Override
public double getPitch() {
return m_gyro.getPitch();
}

@Override
public double getRoll() {
return m_gyro.getRoll();
}

private AHRS m_gyro;

public NavXGyro(final I2C.Port port) {
m_gyro = new AHRS(port);
// NOTE: It takes a bit of time until the gyro reader thread updates
// the connected status, so we can't check it immediately.
// TODO: Replace this with a status indicator
/*if (!m_gyro.isConnected()) {
Logger.get(Category.HAL).logData(Severity.ERROR, "NavX Gyro is not connected!");
} else {
Logger.get(Category.HAL).logData(Severity.INFO, "NavX Gyro is connected");
}*/
}

@Override
public void calibrate() {
// m_gyro.calibrate(); calibrate() seems to have been removed.
// it may have been a no-op anyway?
// https://github.com/kauailabs/navxmxp/blob/master/roborio/java/navx_frc/src/com/kauailabs/navx/frc/AHRS.java
}

@Override
public void reset() {
m_gyro.reset();
}

@Override
public double getAngle() {
return m_gyro.getAngle();
}

@Override
public double getRate() {
return m_gyro.getRate();
}

@Override
public double getPitch() {
return m_gyro.getPitch();
}

@Override
public double getRoll() {
return m_gyro.getRoll();
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -3,9 +3,9 @@
import static com.team766.robot.gatorade.constants.ConfigConstants.*;

import com.ctre.phoenix.motorcontrol.NeutralMode;
import com.revrobotics.CANSparkBase.ControlType;
import com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkMax.ControlType;
import com.revrobotics.SparkMaxPIDController;
import com.revrobotics.SparkPIDController;
import com.team766.config.ConfigFileReader;
import com.team766.framework.Mechanism;
import com.team766.hal.MotorController;
Expand Down Expand Up @@ -58,7 +58,7 @@ private double getHeight() {

private final CANSparkMax leftMotor;
private final CANSparkMax rightMotor;
private final SparkMaxPIDController pidController;
private final SparkPIDController pidController;
private final ValueProvider<Double> pGain;
private final ValueProvider<Double> iGain;
private final ValueProvider<Double> dGain;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,9 +3,9 @@
import static com.team766.robot.gatorade.constants.ConfigConstants.*;

import com.ctre.phoenix.motorcontrol.NeutralMode;
import com.revrobotics.CANSparkBase.ControlType;
import com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkMax.ControlType;
import com.revrobotics.SparkMaxPIDController;
import com.revrobotics.SparkPIDController;
import com.team766.config.ConfigFileReader;
import com.team766.framework.Mechanism;
import com.team766.hal.MotorController;
Expand Down Expand Up @@ -60,7 +60,7 @@ public double getAngle() {

private final CANSparkMax leftMotor;
private final CANSparkMax rightMotor;
private final SparkMaxPIDController pidController;
private final SparkPIDController pidController;
private final ValueProvider<Double> pGain;
private final ValueProvider<Double> iGain;
private final ValueProvider<Double> dGain;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,9 +2,9 @@

import static com.team766.robot.gatorade.constants.ConfigConstants.*;

import com.revrobotics.CANSparkBase.ControlType;
import com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkMax.ControlType;
import com.revrobotics.SparkMaxPIDController;
import com.revrobotics.SparkPIDController;
import com.team766.config.ConfigFileReader;
import com.team766.framework.Mechanism;
import com.team766.hal.MotorController;
Expand Down Expand Up @@ -59,7 +59,7 @@ private double getAngle() {
private static final double NEAR_THRESHOLD = 5.0;

private final CANSparkMax motor;
private final SparkMaxPIDController pidController;
private final SparkPIDController pidController;
private final ValueProvider<Double> pGain;
private final ValueProvider<Double> iGain;
private final ValueProvider<Double> dGain;
Expand Down
24 changes: 14 additions & 10 deletions vendordeps/navx_frc.json → vendordeps/NavX.json
Original file line number Diff line number Diff line change
@@ -1,26 +1,26 @@
{
"fileName": "navx_frc.json",
"name": "KauaiLabs_navX_FRC",
"version": "4.0.447",
"frcYear": "2024",
"fileName": "NavX.json",
"name": "NavX",
"version": "2024.1.0",
"uuid": "cb311d09-36e9-4143-a032-55bb2b94443b",
"frcYear": "2024",
"mavenUrls": [
"https://repo1.maven.org/maven2/"
"https://dev.studica.com/maven/release/2024/"
],
"jsonUrl": "https://www.kauailabs.com/dist/frc/2022/navx_frc.json",
"jsonUrl": "https://dev.studica.com/releases/2024/NavX.json",
"javaDependencies": [
{
"groupId": "com.kauailabs.navx.frc",
"artifactId": "navx-java",
"version": "4.0.447"
"artifactId": "navx-frc-java",
"version": "2024.1.0"
}
],
"jniDependencies": [],
"cppDependencies": [
{
"groupId": "com.kauailabs.navx.frc",
"artifactId": "navx-cpp",
"version": "4.0.447",
"artifactId": "navx-frc-cpp",
"version": "2024.1.0",
"headerClassifier": "headers",
"sourcesClassifier": "sources",
"sharedLibrary": false,
Expand All @@ -29,6 +29,10 @@
"binaryPlatforms": [
"linuxathena",
"linuxraspbian",
"linuxarm32",
"linuxarm64",
"linuxx86-64",
"osxuniversal",
"windowsx86-64"
]
}
Expand Down
151 changes: 151 additions & 0 deletions vendordeps/Phoenix5.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,151 @@
{
"fileName": "Phoenix5.json",
"name": "CTRE-Phoenix (v5)",
"version": "5.33.0",
"frcYear": 2024,
"uuid": "ab676553-b602-441f-a38d-f1296eff6537",
"mavenUrls": [
"https://maven.ctr-electronics.com/release/"
],
"jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix/Phoenix5-frc2024-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.json",
"onlineUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2024-latest.json"
}
],
"javaDependencies": [
{
"groupId": "com.ctre.phoenix",
"artifactId": "api-java",
"version": "5.33.0"
},
{
"groupId": "com.ctre.phoenix",
"artifactId": "wpiapi-java",
"version": "5.33.0"
}
],
"jniDependencies": [
{
"groupId": "com.ctre.phoenix",
"artifactId": "cci",
"version": "5.33.0",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
"windowsx86-64",
"linuxx86-64",
"linuxathena"
],
"simMode": "hwsim"
},
{
"groupId": "com.ctre.phoenix.sim",
"artifactId": "cci-sim",
"version": "5.33.0",
"isJar": false,
"skipInvalidPlatforms": true,
"validPlatforms": [
"windowsx86-64",
"linuxx86-64",
"osxuniversal"
],
"simMode": "swsim"
}
],
"cppDependencies": [
{
"groupId": "com.ctre.phoenix",
"artifactId": "wpiapi-cpp",
"version": "5.33.0",
"libName": "CTRE_Phoenix_WPI",
"headerClassifier": "headers",
"sharedLibrary": true,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"windowsx86-64",
"linuxx86-64",
"linuxathena"
],
"simMode": "hwsim"
},
{
"groupId": "com.ctre.phoenix",
"artifactId": "api-cpp",
"version": "5.33.0",
"libName": "CTRE_Phoenix",
"headerClassifier": "headers",
"sharedLibrary": true,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"windowsx86-64",
"linuxx86-64",
"linuxathena"
],
"simMode": "hwsim"
},
{
"groupId": "com.ctre.phoenix",
"artifactId": "cci",
"version": "5.33.0",
"libName": "CTRE_PhoenixCCI",
"headerClassifier": "headers",
"sharedLibrary": true,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"windowsx86-64",
"linuxx86-64",
"linuxathena"
],
"simMode": "hwsim"
},
{
"groupId": "com.ctre.phoenix.sim",
"artifactId": "wpiapi-cpp-sim",
"version": "5.33.0",
"libName": "CTRE_Phoenix_WPISim",
"headerClassifier": "headers",
"sharedLibrary": true,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"windowsx86-64",
"linuxx86-64",
"osxuniversal"
],
"simMode": "swsim"
},
{
"groupId": "com.ctre.phoenix.sim",
"artifactId": "api-cpp-sim",
"version": "5.33.0",
"libName": "CTRE_PhoenixSim",
"headerClassifier": "headers",
"sharedLibrary": true,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"windowsx86-64",
"linuxx86-64",
"osxuniversal"
],
"simMode": "swsim"
},
{
"groupId": "com.ctre.phoenix.sim",
"artifactId": "cci-sim",
"version": "5.33.0",
"libName": "CTRE_PhoenixCCISim",
"headerClassifier": "headers",
"sharedLibrary": true,
"skipInvalidPlatforms": true,
"binaryPlatforms": [
"windowsx86-64",
"linuxx86-64",
"osxuniversal"
],
"simMode": "swsim"
}
]
}
Loading