Skip to content
This repository was archived by the owner on May 19, 2024. It is now read-only.

Commit 3975a90

Browse files
committed
refactor(config): Create Phoenix 6 configs.
1 parent 4a21d0c commit 3975a90

File tree

4 files changed

+103
-69
lines changed

4 files changed

+103
-69
lines changed

Diff for: src/main/java/frc/lib/config/AbsoluteEncoderConfig.java

+33
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,8 @@
11
package frc.lib.config;
22

3+
import com.ctre.phoenix6.configs.CANcoderConfiguration;
4+
import com.ctre.phoenix6.configs.MagnetSensorConfigs;
5+
import com.ctre.phoenix6.signals.SensorDirectionValue;
36
import edu.wpi.first.math.geometry.Rotation2d;
47

58
/** Absolute encoder config. */
@@ -73,4 +76,34 @@ public double sensorToMechanismRatio() {
7376
public Rotation2d offset() {
7477
return offset;
7578
}
79+
80+
/**
81+
* Creates Phoenix 6 magnet sensor configs.
82+
*
83+
* @return Phoenix 6 magnet sensor configs.
84+
*/
85+
private MagnetSensorConfigs createMagnetSensorConfigs() {
86+
final MagnetSensorConfigs magnetSensorConfigs = new MagnetSensorConfigs();
87+
88+
magnetSensorConfigs.MagnetOffset = offset().getRotations();
89+
magnetSensorConfigs.SensorDirection =
90+
ccwPositive()
91+
? SensorDirectionValue.CounterClockwise_Positive
92+
: SensorDirectionValue.Clockwise_Positive;
93+
94+
return magnetSensorConfigs;
95+
}
96+
97+
/**
98+
* Creates a Phoenix 6 CANcoder config.
99+
*
100+
* @return a Phoenix 6 CANcoder config.
101+
*/
102+
public CANcoderConfiguration createCANcoderConfig() {
103+
final CANcoderConfiguration cancoderConfig = new CANcoderConfiguration();
104+
105+
cancoderConfig.MagnetSensor = createMagnetSensorConfigs();
106+
107+
return cancoderConfig;
108+
}
76109
}

Diff for: src/main/java/frc/lib/config/MotorConfig.java

+62
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,11 @@
11
package frc.lib.config;
22

3+
import com.ctre.phoenix6.configs.CurrentLimitsConfigs;
4+
import com.ctre.phoenix6.configs.MotorOutputConfigs;
5+
import com.ctre.phoenix6.configs.TalonFXConfiguration;
6+
import com.ctre.phoenix6.signals.InvertedValue;
7+
import com.ctre.phoenix6.signals.NeutralModeValue;
8+
39
/** Motor config. */
410
public class MotorConfig {
511

@@ -94,4 +100,60 @@ public double motorToMechanismRatio() {
94100
public double currentLimitAmps() {
95101
return currentLimitAmps;
96102
}
103+
104+
/**
105+
* Creates Phoenix 6 current limit configs.
106+
*
107+
* @return Phoenix 6 current limit configs.
108+
*/
109+
private CurrentLimitsConfigs createCurrentLimitsConfigs() {
110+
final CurrentLimitsConfigs currentLimitsConfigs = new CurrentLimitsConfigs();
111+
112+
// Stator current is a measure of the current inside of the motor and is typically higher than
113+
// supply (breaker) current
114+
currentLimitsConfigs.StatorCurrentLimit = currentLimitAmps() * 2.0;
115+
currentLimitsConfigs.StatorCurrentLimitEnable = true;
116+
117+
currentLimitsConfigs.SupplyCurrentLimit = currentLimitAmps();
118+
// Allow higher current spikes (150%) for a brief duration (one second)
119+
// REV 40A auto-resetting breakers typically trip when current exceeds 300% for one second
120+
currentLimitsConfigs.SupplyCurrentThreshold = currentLimitAmps() * 1.5;
121+
currentLimitsConfigs.SupplyTimeThreshold = 1;
122+
currentLimitsConfigs.SupplyCurrentLimitEnable = true;
123+
124+
return currentLimitsConfigs;
125+
}
126+
127+
/**
128+
* Creates Phoenix 6 motor output configs.
129+
*
130+
* @return Phoenix 6 motor output configs.
131+
*/
132+
private MotorOutputConfigs createMotorOutputConfigs() {
133+
final MotorOutputConfigs motorOutputConfigs = new MotorOutputConfigs();
134+
135+
motorOutputConfigs.Inverted =
136+
ccwPositive() ? InvertedValue.CounterClockwise_Positive : InvertedValue.Clockwise_Positive;
137+
motorOutputConfigs.NeutralMode =
138+
neutralBrake() ? NeutralModeValue.Brake : NeutralModeValue.Coast;
139+
140+
return motorOutputConfigs;
141+
}
142+
143+
/**
144+
* Creates a Phoenix 6 TalonFX config.
145+
*
146+
* @return a Phoenix 6 TalonFX config.
147+
*/
148+
public TalonFXConfiguration createTalonFXConfig() {
149+
final TalonFXConfiguration talonFXConfig = new TalonFXConfiguration();
150+
151+
talonFXConfig.MotorOutput = createMotorOutputConfigs();
152+
153+
talonFXConfig.CurrentLimits = createCurrentLimitsConfigs();
154+
155+
talonFXConfig.Feedback.SensorToMechanismRatio = motorToMechanismRatio();
156+
157+
return talonFXConfig;
158+
}
97159
}

Diff for: src/main/java/frc/lib/controller/PositionControllerIOTalonFX2.java

+6-41
Original file line numberDiff line numberDiff line change
@@ -2,16 +2,11 @@
22

33
import com.ctre.phoenix6.BaseStatusSignal;
44
import com.ctre.phoenix6.StatusSignal;
5-
import com.ctre.phoenix6.configs.CANcoderConfiguration;
6-
import com.ctre.phoenix6.configs.TalonFXConfiguration;
75
import com.ctre.phoenix6.controls.Follower;
86
import com.ctre.phoenix6.controls.VoltageOut;
97
import com.ctre.phoenix6.hardware.CANcoder;
108
import com.ctre.phoenix6.hardware.ParentDevice;
119
import com.ctre.phoenix6.hardware.TalonFX;
12-
import com.ctre.phoenix6.signals.InvertedValue;
13-
import com.ctre.phoenix6.signals.NeutralModeValue;
14-
import com.ctre.phoenix6.signals.SensorDirectionValue;
1510
import edu.wpi.first.math.controller.ArmFeedforward;
1611
import edu.wpi.first.math.controller.PIDController;
1712
import edu.wpi.first.math.util.Units;
@@ -84,43 +79,13 @@ public void configure() {
8479

8580
ParentDevice.optimizeBusUtilizationForAll(leaderMotor, followerMotor, encoder);
8681

87-
TalonFXConfiguration motorConfig = new TalonFXConfiguration();
82+
Configurator.configureTalonFX(
83+
leaderMotor.getConfigurator(), config.motorConfig().createTalonFXConfig());
84+
Configurator.configureTalonFX(
85+
followerMotor.getConfigurator(), config.motorConfig().createTalonFXConfig());
8886

89-
motorConfig.MotorOutput.Inverted =
90-
config.motorConfig().ccwPositive()
91-
? InvertedValue.CounterClockwise_Positive
92-
: InvertedValue.Clockwise_Positive;
93-
motorConfig.MotorOutput.NeutralMode =
94-
config.motorConfig().neutralBrake() ? NeutralModeValue.Brake : NeutralModeValue.Coast;
95-
96-
// Stator current is a measure of the current inside of the motor and is typically higher than
97-
// supply (breaker) current
98-
motorConfig.CurrentLimits.StatorCurrentLimit = config.motorConfig().currentLimitAmps() * 2.0;
99-
motorConfig.CurrentLimits.StatorCurrentLimitEnable = true;
100-
101-
motorConfig.CurrentLimits.SupplyCurrentLimit = config.motorConfig().currentLimitAmps();
102-
// Allow higher current spikes (150%) for a brief duration (one second)
103-
// REV 40A auto-resetting breakers typically trip when current exceeds 300% for one second
104-
motorConfig.CurrentLimits.SupplyCurrentThreshold =
105-
config.motorConfig().currentLimitAmps() * 1.5;
106-
motorConfig.CurrentLimits.SupplyTimeThreshold = 1;
107-
motorConfig.CurrentLimits.SupplyCurrentLimitEnable = true;
108-
109-
motorConfig.Feedback.SensorToMechanismRatio = config.motorConfig().motorToMechanismRatio();
110-
111-
Configurator.configureTalonFX(leaderMotor.getConfigurator(), motorConfig);
112-
Configurator.configureTalonFX(followerMotor.getConfigurator(), motorConfig);
113-
114-
CANcoderConfiguration encoderConfig = new CANcoderConfiguration();
115-
116-
encoderConfig.MagnetSensor.MagnetOffset =
117-
config.absoluteEncoderConfig().offset().getRotations();
118-
encoderConfig.MagnetSensor.SensorDirection =
119-
config.absoluteEncoderConfig().ccwPositive()
120-
? SensorDirectionValue.CounterClockwise_Positive
121-
: SensorDirectionValue.Clockwise_Positive;
122-
123-
Configurator.configureCANcoder(encoder.getConfigurator(), encoderConfig);
87+
Configurator.configureCANcoder(
88+
encoder.getConfigurator(), config.absoluteEncoderConfig().createCANcoderConfig());
12489
}
12590

12691
@Override

Diff for: src/main/java/frc/lib/controller/VelocityControllerIOTalonFX.java

+2-28
Original file line numberDiff line numberDiff line change
@@ -2,11 +2,8 @@
22

33
import com.ctre.phoenix6.BaseStatusSignal;
44
import com.ctre.phoenix6.StatusSignal;
5-
import com.ctre.phoenix6.configs.TalonFXConfiguration;
65
import com.ctre.phoenix6.hardware.ParentDevice;
76
import com.ctre.phoenix6.hardware.TalonFX;
8-
import com.ctre.phoenix6.signals.InvertedValue;
9-
import com.ctre.phoenix6.signals.NeutralModeValue;
107
import frc.lib.CAN;
118
import frc.lib.Configurator;
129
import frc.lib.config.MechanismConfig;
@@ -42,31 +39,8 @@ public void configure() {
4239

4340
ParentDevice.optimizeBusUtilizationForAll(motor);
4441

45-
TalonFXConfiguration motorConfig = new TalonFXConfiguration();
46-
47-
motorConfig.MotorOutput.Inverted =
48-
config.motorConfig().ccwPositive()
49-
? InvertedValue.CounterClockwise_Positive
50-
: InvertedValue.Clockwise_Positive;
51-
motorConfig.MotorOutput.NeutralMode =
52-
config.motorConfig().neutralBrake() ? NeutralModeValue.Brake : NeutralModeValue.Coast;
53-
54-
// Stator current is a measure of the current inside of the motor and is typically higher than
55-
// supply (breaker) current
56-
motorConfig.CurrentLimits.StatorCurrentLimit = config.motorConfig().currentLimitAmps() * 2.0;
57-
motorConfig.CurrentLimits.StatorCurrentLimitEnable = true;
58-
59-
motorConfig.CurrentLimits.SupplyCurrentLimit = config.motorConfig().currentLimitAmps();
60-
// Allow higher current spikes (150%) for a brief duration (one second)
61-
// REV 40A auto-resetting breakers typically trip when current exceeds 300% for one second
62-
motorConfig.CurrentLimits.SupplyCurrentThreshold =
63-
config.motorConfig().currentLimitAmps() * 1.5;
64-
motorConfig.CurrentLimits.SupplyTimeThreshold = 1;
65-
motorConfig.CurrentLimits.SupplyCurrentLimitEnable = true;
66-
67-
motorConfig.Feedback.SensorToMechanismRatio = config.motorConfig().motorToMechanismRatio();
68-
69-
Configurator.configureTalonFX(motor.getConfigurator(), motorConfig);
42+
Configurator.configureTalonFX(
43+
motor.getConfigurator(), config.motorConfig().createTalonFXConfig());
7044
}
7145

7246
@Override

0 commit comments

Comments
 (0)