Skip to content

Commit

Permalink
Add Advantage kit to Swerve and Update to 2024 Phoenix 6 (#205)
Browse files Browse the repository at this point in the history
  • Loading branch information
legoguy1000 committed Jan 27, 2024
1 parent 5e0ea52 commit b6f34bc
Show file tree
Hide file tree
Showing 28 changed files with 890 additions and 868 deletions.
2 changes: 2 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -177,3 +177,5 @@ logs/

# Folder that has CTRE Phoenix Sim device config storage
ctre_sim/

BuildConstants.java
35 changes: 35 additions & 0 deletions build.gradle
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
plugins {
id "java"
id "edu.wpi.first.GradleRIO" version "2024.2.1"
id "com.peterabeles.gversion" version "1.10"
}

java {
Expand All @@ -14,6 +15,27 @@ repositories {

def ROBOT_MAIN_CLASS = "frc.robot.Main"

repositories {
maven {
url = uri("https://maven.pkg.github.com/Mechanical-Advantage/AdvantageKit")
credentials {
username = "Mechanical-Advantage-Bot"
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"
}
}
mavenLocal()
}

configurations.all {
exclude group: "edu.wpi.first.wpilibj"
}

task(checkAkitInstall, dependsOn: "classes", type: JavaExec) {
mainClass = "org.littletonrobotics.junction.CheckInstall"
classpath = sourceSets.main.runtimeClasspath
}
compileJava.finalizedBy checkAkitInstall

// Define my targets (RoboRIO) and artifacts (deployable files)
// This is added by GradleRIO's backing project DeployUtils.
deploy {
Expand Down Expand Up @@ -74,6 +96,8 @@ dependencies {
testImplementation 'org.junit.jupiter:junit-jupiter:5.10.1'
annotationProcessor 'com.github.Frc5572:RobotTools:main-SNAPSHOT'

def akitJson = new groovy.json.JsonSlurper().parseText(new File(projectDir.getAbsolutePath() + "/vendordeps/AdvantageKit.json").text)
annotationProcessor "org.littletonrobotics.akit.junction:junction-autolog:$akitJson.version"
}

test {
Expand Down Expand Up @@ -119,3 +143,14 @@ javadoc {
"</script>"
}
}

// Create version file
project.compileJava.dependsOn(createVersionFile)
gversion {
srcDir = "src/main/java/"
classPackage = "frc.robot"
className = "BuildConstants"
dateFormat = "yyyy-MM-dd HH:mm:ss z"
timeZone = "America/New_York"
indent = " "
}
96 changes: 25 additions & 71 deletions src/main/java/frc/lib/math/Conversions.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,93 +3,48 @@
import edu.wpi.first.math.MathUtil;

/**
* Mathematical conversions for swerve calculations
* Static Conversion functions
*/
public class Conversions {

/**
* @param counts Falcon Counts
* @param gearRatio Gear Ratio between Falcon and Mechanism
* @return Degrees of Rotation of Mechanism falconToDegrees
* @param wheelRPS Wheel Velocity: (in Rotations per Second)
* @param circumference Wheel Circumference: (in Meters)
* @return Wheel Velocity: (in Meters per Second)
*/
public static double falconToDegrees(double counts, double gearRatio) {
return counts * (360.0 / (gearRatio * 2048.0));
}

/**
* @param degrees Degrees of rotation of Mechanism
* @param gearRatio Gear Ratio between Falcon and Mechanism
* @return Falcon Counts degreesToFalcon
*/
public static double degreesToFalcon(double degrees, double gearRatio) {
double ticks = degrees / (360.0 / (gearRatio * 2048.0));
return ticks;
}

/**
* @param velocityCounts Falcon Velocity Counts
* @param gearRatio Gear Ratio between Falcon and Mechanism (set to 1 for Falcon RPM)
* @return RPM of Mechanism
*/
public static double falconToRPM(double velocityCounts, double gearRatio) {
double motorRPM = velocityCounts * (600.0 / 2048.0);
double mechRPM = motorRPM / gearRatio;
return mechRPM;
}

/**
* @param rpm RPM of mechanism
* @param gearRatio Gear Ratio between Falcon and Mechanism (set to 1 for Falcon RPM)
* @return RPM of Mechanism
*/
public static double rpmToFalcon(double rpm, double gearRatio) {
double motorRPM = rpm * gearRatio;
double sensorCounts = motorRPM * (2048.0 / 600.0);
return sensorCounts;
}

/**
* @param counts Falcon Counts
* @param gearRatio Gear Ratio between Falcon and Mechanism
* @return Degrees of Rotation of Mechanism falconToDegrees
*/
public static double falconToMeters(double counts, double gearRatio, double circumference) {
return counts * circumference / (gearRatio * 2048.0);
public static double rpsToMPS(double wheelRPS, double circumference) {
double wheelMPS = wheelRPS * circumference;
return wheelMPS;
}

/**
* @param velocitycounts Falcon Velocity Counts
* @param circumference Circumference of Wheel
* @param gearRatio Gear Ratio between Falcon and Mechanism (set to 1 for Falcon RPM)
* @return Falcon Velocity Counts
* @param wheelMPS Wheel Velocity: (in Meters per Second)
* @param circumference Wheel Circumference: (in Meters)
* @return Wheel Velocity: (in Rotations per Second)
*/
public static double falconToMPS(double velocitycounts, double circumference,
double gearRatio) {
double wheelRPM = falconToRPM(velocitycounts, gearRatio);
double wheelMPS = (wheelRPM * circumference) / 60;
return wheelMPS;
public static double mpsToRPS(double wheelMPS, double circumference) {
double wheelRPS = wheelMPS / circumference;
return wheelRPS;
}

/**
* @param velocity Velocity MPS
* @param circumference Circumference of Wheel
* @param gearRatio Gear Ratio between Falcon and Mechanism (set to 1 for Falcon RPM)
* @return Falcon Velocity Counts
* @param wheelRotations Wheel Position: (in Rotations)
* @param circumference Wheel Circumference: (in Meters)
* @return Wheel Distance: (in Meters)
*/
public static double mpsToFalcon(double velocity, double circumference, double gearRatio) {
double wheelRPM = ((velocity * 60) / circumference);
double wheelVelocity = rpmToFalcon(wheelRPM, gearRatio);
return wheelVelocity;
public static double rotationsToMeters(double wheelRotations, double circumference) {
double wheelMeters = wheelRotations * circumference;
return wheelMeters;
}

/**
* Normalize angle to between 0 to 360
*
* @param goal initial angle
* @return normalized angle
* @param wheelMeters Wheel Distance: (in Meters)
* @param circumference Wheel Circumference: (in Meters)
* @return Wheel Position: (in Rotations)
*/
public static double reduceTo0_360(double goal) {
return goal % 360;
public static double metersToRotations(double wheelMeters, double circumference) {
double wheelRotations = wheelMeters / circumference;
return wheelRotations;
}

/**
Expand All @@ -113,7 +68,6 @@ public static double applySwerveCurve(double input, double deadband) {
processedInput = Math.copySign(processedInput, input);
}
return MathUtil.clamp(processedInput, -1, 1);

}

/**
Expand Down
65 changes: 0 additions & 65 deletions src/main/java/frc/lib/util/ctre/CTREConfigs.java

This file was deleted.

61 changes: 0 additions & 61 deletions src/main/java/frc/lib/util/ctre/CTREModuleState.java

This file was deleted.

Loading

0 comments on commit b6f34bc

Please sign in to comment.