Skip to content

Commit

Permalink
added current limits to swerve drive motors (make sure it works tho)
Browse files Browse the repository at this point in the history
  • Loading branch information
PGgit08 committed Mar 25, 2024
1 parent b99876e commit e3519ff
Show file tree
Hide file tree
Showing 3 changed files with 18 additions and 13 deletions.
1 change: 0 additions & 1 deletion src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -149,7 +149,6 @@ public static class Presets {
public static final double SHOOTER_AMP_HANDOFF = 50;
public static final double ELEVATOR_AMP_HANDOFF = 0.04;

// TODO: get values for these
public static final InterpolatingDoubleTreeMap SHOOTER_DISTANCE_ANGLE = new InterpolatingDoubleTreeMap();

static {
Expand Down
28 changes: 18 additions & 10 deletions src/main/java/frc/robot/utils/SwerveModule.java
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
/* Copyright (C) 2024 Team 334. All Rights Reserved.*/
package frc.robot.utils;

import com.ctre.phoenix6.configs.CurrentLimitsConfigs;
import com.ctre.phoenix6.hardware.CANcoder;
import com.ctre.phoenix6.hardware.TalonFX;
import edu.wpi.first.math.MathUtil;
Expand Down Expand Up @@ -51,18 +52,8 @@ public class SwerveModule {
public SwerveModule(String name, int driveMotorId, int rotationMotorId, int encoderId) {
_driveMotor = new TalonFX(driveMotorId);
_rotationMotor = new TalonFX(rotationMotorId);

// NO NEED FOR THIS CODE ANYMORE, FIGURED HOW TO DO OFFSETS IN PHOENIX TUNER
// new stuff because CTRE update
// MagnetSensorConfigs encoderConfig = new MagnetSensorConfigs();
// encoderConfig.AbsoluteSensorRange =
// AbsoluteSensorRangeValue.Signed_PlusMinusHalf;
// encoderConfig.MagnetOffset = (angleOffset / 180) / 2;

_encoder = new CANcoder(encoderId);

// _encoder.getConfigurator().apply(encoderConfig);

_name = name;

_driveController = new PIDController(PID.MODULE_DRIVE_KP, 0, 0);
Expand All @@ -72,12 +63,29 @@ public SwerveModule(String name, int driveMotorId, int rotationMotorId, int enco

TalonFXConfig.configureFalcon(_driveMotor, false);
TalonFXConfig.configureFalcon(_rotationMotor, true);

// TODO: make sure this works
CurrentLimitsConfigs currentConfig = new CurrentLimitsConfigs();

currentConfig.SupplyCurrentLimit = 60;
currentConfig.SupplyCurrentThreshold = 30;
currentConfig.SupplyTimeThreshold = 0.9;

currentConfig.StatorCurrentLimit = 120;

currentConfig.SupplyCurrentLimitEnable = false;
currentConfig.StatorCurrentLimitEnable = false;

_driveMotor.getConfigurator().apply(currentConfig);
}

/** Display's this module's info on SmartDashboard through a supplied builder. */
public void displayInfo(SendableBuilder builder) {
builder.addDoubleProperty(_name + " Angle", () -> getAngle(), null);
builder.addDoubleProperty(_name + " Velocity", () -> getDriveVelocity(), null);

builder.addDoubleProperty(_name + " Drive Supply Current", () -> _driveMotor.getSupplyCurrent().getValueAsDouble(), null);
builder.addDoubleProperty(_name + " Drive Stator Current", () -> _driveMotor.getStatorCurrent().getValueAsDouble(), null);
}

/**
Expand Down
2 changes: 0 additions & 2 deletions src/main/java/frc/robot/utils/configs/TalonFXConfig.java
Original file line number Diff line number Diff line change
Expand Up @@ -43,8 +43,6 @@ public static TalonFXConfiguration configureFalcon(TalonFX falcon, boolean inver
config.SoftwareLimitSwitch.ForwardSoftLimitEnable = false;
config.SoftwareLimitSwitch.ReverseSoftLimitEnable = false;

// config.CurrentLimits.StatorCurrentLimit = 80; // TODO: Find

falcon.getConfigurator().apply(config);
falcon.setPosition(0);

Expand Down

0 comments on commit e3519ff

Please sign in to comment.