Skip to content

Commit

Permalink
Misc
Browse files Browse the repository at this point in the history
  • Loading branch information
weerobots committed Jan 14, 2024
1 parent 2285376 commit 57aaaa4
Show file tree
Hide file tree
Showing 3 changed files with 10 additions and 7 deletions.
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -76,8 +76,8 @@ public static final class Swerve {
public static final double maxAngularVelocity = 5.0;

/* Neutral Modes */
public static final IdleMode angleNeutralMode = IdleMode.kCoast;
public static final IdleMode driveNeutralMode = IdleMode.kCoast;
public static final IdleMode angleNeutralMode = IdleMode.kBrake;
public static final IdleMode driveNeutralMode = IdleMode.kBrake;

/* Motor Inverts */
public static final boolean driveInvert = false;
Expand Down
1 change: 1 addition & 0 deletions src/main/java/frc/robot/subsystems/Swerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -57,6 +57,7 @@ public void drive(Translation2d translation, double rotation, boolean fieldRelat
for (SwerveModule mod : mSwerveMods) {
mod.setDesiredState(swerveModuleStates[mod.moduleNumber], isOpenLoop);
}
SmartDashboard.putNumber("DRIVE",translation.getX());
}

/* Used by SwerveControllerCommand in Auto */
Expand Down
12 changes: 7 additions & 5 deletions src/main/java/frc/robot/subsystems/SwerveModule.java
Original file line number Diff line number Diff line change
Expand Up @@ -103,16 +103,18 @@ private void configDriveMotor() {
driveMotor.setIdleMode(Constants.Swerve.driveNeutralMode);
driveEncoder.setVelocityConversionFactor(Constants.Swerve.driveConversionVelocityFactor);
driveEncoder.setPositionConversionFactor(Constants.Swerve.driveConversionPositionFactor);
driveController.setP(Constants.Swerve.angleKP);
driveController.setI(Constants.Swerve.angleKI);
driveController.setD(Constants.Swerve.angleKD);
driveController.setFF(Constants.Swerve.angleKFF);
driveController.setP(Constants.Swerve.driveKP);
driveController.setI(Constants.Swerve.driveKI);
driveController.setD(Constants.Swerve.driveKD);
driveController.setFF(Constants.Swerve.driveKFF);
driveMotor.enableVoltageCompensation(Constants.Swerve.voltageComp);
driveMotor.burnFlash();
driveEncoder.setPosition(0.0);
}

private void setSpeed(SwerveModuleState desiredState, boolean isOpenLoop) {

SmartDashboard.putNumber(String.valueOf(moduleNumber) + "SPD", desiredState.speedMetersPerSecond);
if (isOpenLoop) {
double percentOutput = desiredState.speedMetersPerSecond / Constants.Swerve.maxSpeed;
driveMotor.set(percentOutput);
Expand Down Expand Up @@ -156,6 +158,6 @@ public void periodic() {
SmartDashboard.putNumber(String.valueOf(moduleNumber) + " cancoderAbs",
m_turnCancoder.getAbsolutePosition().getValueAsDouble());

SmartDashboard.putNumber("PCF", Constants.Swerve.driveConversionPositionFactor);

}
}

0 comments on commit 57aaaa4

Please sign in to comment.