Skip to content

Commit

Permalink
feat: imported to 2024
Browse files Browse the repository at this point in the history
  • Loading branch information
ProgrammingSR committed Jan 20, 2024
1 parent 05bd2a4 commit 2bfaef8
Show file tree
Hide file tree
Showing 8 changed files with 179 additions and 144 deletions.
2 changes: 1 addition & 1 deletion build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ dependencies {
simulationRelease wpi.sim.enableRelease()

testImplementation 'org.junit.jupiter:junit-jupiter:5.10.1'
testRuntimeOnly 'org.junit.platform:junit-platform-launcher'
//testRuntimeOnly 'org.junit.platform:junit-platform-launcher'
}

test {
Expand Down
1 change: 1 addition & 0 deletions networktables.json
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
[]
97 changes: 97 additions & 0 deletions simgui-ds.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,97 @@
{
"keyboardJoysticks": [
{
"axisConfig": [
{
"decKey": 65,
"incKey": 68
},
{
"decKey": 87,
"incKey": 83
},
{
"decKey": 69,
"decayRate": 0.0,
"incKey": 82,
"keyRate": 0.009999999776482582
}
],
"axisCount": 3,
"buttonCount": 4,
"buttonKeys": [
90,
88,
67,
86
],
"povConfig": [
{
"key0": 328,
"key135": 323,
"key180": 322,
"key225": 321,
"key270": 324,
"key315": 327,
"key45": 329,
"key90": 326
}
],
"povCount": 1
},
{
"axisConfig": [
{
"decKey": 74,
"incKey": 76
},
{
"decKey": 73,
"incKey": 75
}
],
"axisCount": 2,
"buttonCount": 4,
"buttonKeys": [
77,
44,
46,
47
],
"povCount": 0
},
{
"axisConfig": [
{
"decKey": 263,
"incKey": 262
},
{
"decKey": 265,
"incKey": 264
}
],
"axisCount": 2,
"buttonCount": 6,
"buttonKeys": [
260,
268,
266,
261,
269,
267
],
"povCount": 0
},
{
"axisCount": 0,
"buttonCount": 0,
"povCount": 0
}
],
"robotJoysticks": [
{
"guid": "Keyboard0"
}
]
}
18 changes: 18 additions & 0 deletions simgui.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
{
"NTProvider": {
"types": {
"/FMSInfo": "FMSInfo",
"/SmartDashboard/Field": "Field2d"
},
"windows": {
"/SmartDashboard/Field": {
"window": {
"visible": true
}
}
}
},
"NetworkTables Info": {
"visible": true
}
}
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ public static final class DriveConstants {
public static final double kDrivingGearRatio = 8.14; // SDS MK4i's in L1 configuration

// TODO: Tune this PID before running on a robot on the ground
public static final double kPModuleTurningController = -0.3;
public static final double kPModuleTurningController = 0.3;

public static final SwerveDriveKinematics kDriveKinematics = new SwerveDriveKinematics(
new Translation2d(kWheelBase / 2, kTrackWidth / 2),
Expand Down
24 changes: 13 additions & 11 deletions src/main/java/frc/robot/subsystems/SwerveModule.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,8 @@

package frc.robot.subsystems;

import com.ctre.phoenix.sensors.CANCoder;
import com.ctre.phoenix.sensors.SensorTimeBase;
import com.ctre.phoenix6.configs.CANcoderConfiguration;
import com.ctre.phoenix6.hardware.CANcoder;
import com.revrobotics.CANSparkFlex;
import com.revrobotics.CANSparkBase.IdleMode;
import com.revrobotics.CANSparkLowLevel.MotorType;
Expand All @@ -14,6 +14,7 @@
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.kinematics.SwerveModulePosition;
import edu.wpi.first.math.kinematics.SwerveModuleState;
import edu.wpi.first.units.Units;
import frc.robot.Constants.DriveConstants;
import frc.robot.Robot;

Expand All @@ -22,7 +23,7 @@ public class SwerveModule {
private final CANSparkFlex m_driveMotor;
private final CANSparkFlex m_turningMotor;

private final CANCoder m_turningEncoder;
private final CANcoder m_turningEncoder;

private final PIDController m_turningPIDController = new PIDController(DriveConstants.kPModuleTurningController, 0,
0);
Expand Down Expand Up @@ -50,7 +51,7 @@ public SwerveModule(
double turningEncoderOffset) {
m_driveMotor = new CANSparkFlex(driveMotorPort, MotorType.kBrushless);
m_turningMotor = new CANSparkFlex(turningMotorPort, MotorType.kBrushless);
m_turningEncoder = new CANCoder(turningEncoderPort);
m_turningEncoder = new CANcoder(turningEncoderPort);

// converts default units to meters per second
m_driveMotor.getEncoder().setVelocityConversionFactor(
Expand All @@ -59,10 +60,8 @@ public SwerveModule(
m_driveMotor.setInverted(driveMotorReversed);

m_turningMotor.setIdleMode(IdleMode.kBrake);

// converts default units of CANCoders to radians
m_turningEncoder.configFeedbackCoefficient(Math.toRadians(0.087890625), "radians", SensorTimeBase.PerSecond);
m_turningEncoder.configMagnetOffset(-turningEncoderOffset);

m_turningEncoder.getConfigurator().apply(new CANcoderConfiguration().MagnetSensor.withMagnetOffset(-turningEncoderOffset));

m_turningPIDController.enableContinuousInput(-Math.PI, Math.PI);
}
Expand All @@ -79,9 +78,12 @@ public SwerveModulePosition getPosition() {
// actual encoders
// If the robot is simulated, then return the swerve module state using the
// expected values


;
return Robot.isReal()
? new SwerveModulePosition(m_driveMotor.getEncoder().getPosition(),
new Rotation2d(m_turningEncoder.getAbsolutePosition()))
new Rotation2d(Units.RadiansPerSecond.convertFrom(m_turningEncoder.getAbsolutePosition().getValueAsDouble(), Units.RotationsPerSecond)))
: new SwerveModulePosition(m_distance, m_state.angle);
}

Expand All @@ -91,11 +93,11 @@ public SwerveModulePosition getPosition() {
* @param desiredState Desired state with speed and angle.
*/
public void setDesiredState(SwerveModuleState desiredState) {
m_state = SwerveModuleState.optimize(desiredState, new Rotation2d(m_turningEncoder.getAbsolutePosition()));
m_state = SwerveModuleState.optimize(desiredState, new Rotation2d(Units.RadiansPerSecond.convertFrom(m_turningEncoder.getAbsolutePosition().getValueAsDouble(), Units.RotationsPerSecond)));

driveOutput = m_state.speedMetersPerSecond / DriveConstants.kMaxSpeedMetersPerSecond;

turnOutput = m_turningPIDController.calculate(m_turningEncoder.getAbsolutePosition(),
turnOutput = m_turningPIDController.calculate(Units.RadiansPerSecond.convertFrom(m_turningEncoder.getAbsolutePosition().getValueAsDouble(), Units.RotationsPerSecond),
m_state.angle.getRadians());

m_driveMotor.set(driveOutput);
Expand Down
13 changes: 7 additions & 6 deletions vendordeps/NavX.json
Original file line number Diff line number Diff line change
@@ -1,25 +1,26 @@
{
"fileName": "NavX.json",
"name": "KauaiLabs_navX_FRC",
"version": "2023.0.4",
"name": "NavX",
"version": "2024.1.0",
"uuid": "cb311d09-36e9-4143-a032-55bb2b94443b",
"frcYear": "2024",
"mavenUrls": [
"https://dev.studica.com/maven/release/2023/"
"https://dev.studica.com/maven/release/2024/"
],
"jsonUrl": "https://dev.studica.com/releases/2023/NavX.json",
"jsonUrl": "https://dev.studica.com/releases/2024/NavX.json",
"javaDependencies": [
{
"groupId": "com.kauailabs.navx.frc",
"artifactId": "navx-frc-java",
"version": "2023.0.4"
"version": "2024.1.0"
}
],
"jniDependencies": [],
"cppDependencies": [
{
"groupId": "com.kauailabs.navx.frc",
"artifactId": "navx-frc-cpp",
"version": "2023.0.4",
"version": "2024.1.0",
"headerClassifier": "headers",
"sourcesClassifier": "sources",
"sharedLibrary": false,
Expand Down
Loading

0 comments on commit 2bfaef8

Please sign in to comment.