Skip to content

Commit

Permalink
some things
Browse files Browse the repository at this point in the history
  • Loading branch information
bbdriverstation committed Mar 3, 2025
1 parent 1dae337 commit 8425c19
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 2 deletions.
2 changes: 2 additions & 0 deletions src/main/java/frc/robot/constants/DriveConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -89,6 +89,8 @@ public class DriveConstants {
// Drive Velocity firmware PID gains
public static final double driveKp = 0.0;
public static final double driveKd = 0.0;

public static final double driveKa = 0;
public static final double driveKs = 0.0;
public static final double driveKv = 0.1;
public static final double driveSimP = 0.05;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@
import com.ctre.phoenix6.StatusSignal;
import com.ctre.phoenix6.configs.AudioConfigs;
import com.ctre.phoenix6.configs.CANcoderConfiguration;
import com.ctre.phoenix6.configs.Slot0Configs;
import com.ctre.phoenix6.configs.TalonFXConfiguration;
import com.ctre.phoenix6.controls.*;
import com.ctre.phoenix6.hardware.ParentDevice;
Expand Down Expand Up @@ -52,7 +53,7 @@
import java.util.function.DoubleSupplier;

/**
* Module IO implementation for Spark Flex drive motor controller, Spark Max turn motor controller,
* Module IO implementation for TalonFX drive motor controller, Spark Max turn motor controller,
* and duty cycle absolute encoder.
*/
public class ModuleIOHybrid implements ModuleIO {
Expand Down Expand Up @@ -125,7 +126,7 @@ public ModuleIOHybrid(int module, SwerveModuleConstants<TalonFXConfiguration, Ta
// Configure drive motor
var driveConfig = new TalonFXConfiguration().withAudio(new AudioConfigs().withBeepOnBoot(true));
driveConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake;
driveConfig.Slot0 = constants.DriveMotorGains;
driveConfig.Slot0 = new Slot0Configs().withKP(driveKp).withKD(driveKd).withKV(driveKv).withKA(driveKa).withKS(driveKs);
driveConfig.Feedback.SensorToMechanismRatio = driveMotorReduction;
driveConfig.TorqueCurrent.PeakForwardTorqueCurrent = driveMotorCurrentLimit;
driveConfig.TorqueCurrent.PeakReverseTorqueCurrent = -driveMotorCurrentLimit;
Expand Down

0 comments on commit 8425c19

Please sign in to comment.