Skip to content
Draft
2 changes: 1 addition & 1 deletion .project
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<?xml version="1.0" encoding="UTF-8"?>
<projectDescription>
<name>RoboLib</name>
<name>potential-octo-eureka-RoboLib</name>
<comment>Project RoboLib created by Buildship.</comment>
<projects>
</projects>
Expand Down
5 changes: 5 additions & 0 deletions gradle.properties
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
wpiVersion = 2026.2.1

ctreVersion = 26.1.0

advantageKitVersion = 4.0.0
20 changes: 20 additions & 0 deletions lib/.classpath
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
<?xml version="1.0" encoding="UTF-8"?>
<classpath>
<classpathentry kind="src" output="bin/main" path="src/main/java">
<attributes>
<attribute name="gradle_scope" value="main"/>
<attribute name="gradle_used_by_scope" value="main,test"/>
</attributes>
</classpathentry>
<classpathentry kind="src" output="bin/test" path="src/test/java">
<attributes>
<attribute name="gradle_scope" value="test"/>
<attribute name="gradle_used_by_scope" value="test"/>
<attribute name="test" value="true"/>
</attributes>
</classpathentry>
<classpathentry kind="src" path="build/generated/sources/annotationProcessor/java/main"/>
<classpathentry kind="con" path="org.eclipse.jdt.launching.JRE_CONTAINER/org.eclipse.jdt.internal.debug.ui.launcher.StandardVMType/JavaSE-17/"/>
<classpathentry kind="con" path="org.eclipse.buildship.core.gradleclasspathcontainer"/>
<classpathentry kind="output" path="bin/default"/>
</classpath>
34 changes: 34 additions & 0 deletions lib/.project
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
<?xml version="1.0" encoding="UTF-8"?>
<projectDescription>
<name>RoboLib-lib</name>
<comment>Project lib created by Buildship.</comment>
<projects>
</projects>
<buildSpec>
<buildCommand>
<name>org.eclipse.jdt.core.javabuilder</name>
<arguments>
</arguments>
</buildCommand>
<buildCommand>
<name>org.eclipse.buildship.core.gradleprojectbuilder</name>
<arguments>
</arguments>
</buildCommand>
</buildSpec>
<natures>
<nature>org.eclipse.jdt.core.javanature</nature>
<nature>org.eclipse.buildship.core.gradleprojectnature</nature>
</natures>
<filteredResources>
<filter>
<id>1743377880685</id>
<name></name>
<type>30</type>
<matcher>
<id>org.eclipse.core.resources.regexFilterMatcher</id>
<arguments>node_modules|\.git|__CREATED_BY_JAVA_LANGUAGE_SERVER__</arguments>
</matcher>
</filter>
</filteredResources>
</projectDescription>
9 changes: 6 additions & 3 deletions lib/build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -25,14 +25,14 @@ repositories {
mavenLocal()
gradlePluginPortal()

maven {url "https://maven.photonvision.org/repository/snapshots"}
maven {url "https://maven.photonvision.org/repository/internal"}
maven {url "https://maven.ctr-electronics.com/release/"}
maven {url "https://frcmaven.wpi.edu/artifactory/littletonrobotics-mvn-release/"}
}

dependencies {
// Use JUnit Jupiter for testing.
testImplementation 'org.junit.jupiter:junit-jupiter:5.8.1'
testImplementation 'org.junit.jupiter:junit-jupiter:5.10.1'
testRuntimeOnly 'org.junit.platform:junit-platform-launcher'

// WPI Lib
implementation "edu.wpi.first.cscore:cscore-java:$wpiVersion"
Expand All @@ -48,6 +48,9 @@ dependencies {
// CTRE Phoenix 6
implementation "com.ctre.phoenix6:wpiapi-java:${ctreVersion}"

// AdvantageKit
implementation "org.littletonrobotics.akit:akit-java:${advantageKitVersion}"

}

tasks.named('test') {
Expand Down

This file was deleted.

Original file line number Diff line number Diff line change
@@ -0,0 +1,195 @@
package org.fairportrobotics.frc.robolib.drivesystems.swerve;

import java.util.ArrayList;

import com.ctre.phoenix6.CANBus;

import edu.wpi.first.math.geometry.Translation2d;

public class SwerveBuilder {

ArrayList<SwerveModule> modules = new ArrayList<SwerveModule>();
CANBus canBusObj;

private double maxAngularVelRadiansSecond = 1.0;
private double maxLinearVelMetersSecond = Math.PI;

private int pigeonId;

public SwerveBuilder() {

}

public SwerveBuilder withPigeonId(int pigeonId) {
this.pigeonId = pigeonId;
return this;
}

public SwerveBuilder withCanbusName(String canBusname) {
this.canBusObj = new CANBus(canBusname);
return this;
}

public SwerveBuilder withSwerveModule(SwerveModule module) {
this.modules.add(module);
return this;
}

/**
* Set the max linear velocity in meters per second
*
* @param maxVel Max linear velocity in meters per second
* @return The swerve builder
*/
public SwerveBuilder withMaxLinearVelocity(double maxVel) {
this.maxLinearVelMetersSecond = maxVel;
return this;
}

/**
* Set the max angular velocity in radians per second
*
* @param maxVel Max angular velocity in radians per second
* @return The swerve builder
*/
public SwerveBuilder withMaxAngularVelocity(double maxVel) {
this.maxAngularVelRadiansSecond = maxVel;
return this;
}

public SwerveDriveSystem build() {
return new SwerveDriveSystem(pigeonId, canBusObj, maxLinearVelMetersSecond, maxAngularVelRadiansSecond,
modules.toArray(size -> new SwerveModule[size]));
}

public class SwerveModuleBuilder {

private int driveMotorId;
private double driveKP;
private double driveKI;
private double driveKD;
private double driveKV;
private boolean driveInverted = false;
private int steerMotorId;
private double steerKP;
private double steerKI;
private double steerKD;
private double steerKS;
private double steerKV;
private double steerKA;
private int steerEncoderId;
private double steerOffset;
private Translation2d moduleLocation;
private double gearRatio;
private double wheelDiameterInMeters;
private String moduleName;

public SwerveModuleBuilder() {

}

public SwerveModuleBuilder withDriveMotorId(int driveMotorId) {
this.driveMotorId = driveMotorId;
return this;
}

public SwerveModuleBuilder withDriveKP(double driveKP) {
this.driveKP = driveKP;
return this;
}

public SwerveModuleBuilder withDriveKI(double driveKI) {
this.driveKI = driveKI;
return this;
}

public SwerveModuleBuilder withDriveKD(double driveKD) {
this.driveKD = driveKD;
return this;
}

public SwerveModuleBuilder withDriveKV(double driveKV) {
this.driveKV = driveKV;
return this;
}

public SwerveModuleBuilder withDriveInverted(){
this.driveInverted = true;
return this;
}

public SwerveModuleBuilder withSteerMotorId(int steerMotorId) {
this.steerMotorId = steerMotorId;
return this;
}

public SwerveModuleBuilder withSteerKP(double steerKP) {
this.steerKP = steerKP;
return this;
}

public SwerveModuleBuilder withSteerKI(double steerKI) {
this.steerKI = steerKI;
return this;
}

public SwerveModuleBuilder withSteerKD(double steerKD) {
this.steerKD = steerKD;
return this;
}

public SwerveModuleBuilder withSteerKS(double steerKS) {
this.steerKS = steerKS;
return this;
}

public SwerveModuleBuilder withSteerKV(double steerKV) {
this.steerKV = steerKV;
return this;
}

public SwerveModuleBuilder withSteerKA(double steerKA) {
this.steerKA = steerKA;
return this;
}

public SwerveModuleBuilder withSteerEncoderId(int steerEncoderId) {
this.steerEncoderId = steerEncoderId;
return this;
}

public SwerveModuleBuilder withSteerOffset(double offsetRotations) {
this.steerOffset = offsetRotations;
return this;
}

public SwerveModuleBuilder withModuleLocation(Translation2d moduleLocation) {
this.moduleLocation = moduleLocation;
return this;
}

public SwerveModuleBuilder withGearRatio(double gearRatio) {
this.gearRatio = gearRatio;
return this;
}

public SwerveModuleBuilder withWheelDiameter(double wheelDiameterInMeters) {
this.wheelDiameterInMeters = wheelDiameterInMeters;
return this;
}

public SwerveModuleBuilder withModuleName(String moduleName) {
this.moduleName = moduleName;
return this;
}

public SwerveModule build() {
return new SwerveModule(driveMotorId, driveKP, driveKI, driveKD, driveKV, driveInverted, steerMotorId, steerKP, steerKI,
steerKD, steerKS, steerKV, steerKA,
steerEncoderId, steerOffset, canBusObj, moduleLocation, gearRatio, wheelDiameterInMeters,
moduleName);
}

}

}
Loading
Loading