|
2 | 2 | // Open Source Software; you can modify and/or share it under the terms of
|
3 | 3 | // the WPILib BSD license file in the root directory of this project.
|
4 | 4 |
|
5 |
| -package frc.robot.Interfaces; |
| 5 | +package frc.robot.interfaces; |
6 | 6 |
|
7 |
| -import com.ctre.phoenix6.controls.PositionDutyCycle; |
| 7 | +import com.ctre.phoenix6.configs.CANcoderConfiguration; |
| 8 | +import com.ctre.phoenix6.configs.TalonFXConfiguration; |
| 9 | +import com.ctre.phoenix6.controls.MotionMagicExpoVoltage; |
8 | 10 | import com.ctre.phoenix6.hardware.CANcoder;
|
9 | 11 | import com.ctre.phoenix6.hardware.TalonFX;
|
10 |
| - |
| 12 | +import com.ctre.phoenix6.signals.AbsoluteSensorRangeValue; |
| 13 | +import com.ctre.phoenix6.signals.InvertedValue; |
| 14 | +import com.ctre.phoenix6.signals.NeutralModeValue; |
| 15 | +import com.ctre.phoenix6.signals.SensorDirectionValue; |
11 | 16 | import edu.wpi.first.math.geometry.Rotation2d;
|
12 | 17 |
|
13 | 18 | /** Add your docs here. */
|
14 | 19 | public class AngleMotorControl {
|
15 |
| - public static TalonFX[] motor = new TalonFX[4]; |
16 |
| - CANcoder[] CANcoder = new CANcoder[4]; |
17 | 20 |
|
18 |
| - public static final class Mod0 { |
19 |
| - public static final int angleMotorID = 12; |
20 |
| - public static final int canCoderID = 10; |
21 |
| - public static final Rotation2d angleOffset = Rotation2d.fromDegrees(117.334); |
22 |
| - } |
| 21 | + public static class ModConfig { |
| 22 | + public final int m_angleMotorID; |
| 23 | + public final int m_canCoderID; |
| 24 | + public final Rotation2d m_canCoderOffset; |
23 | 25 |
|
24 |
| - /* Front Right Module - Module 1 */ |
25 |
| - public static final class Mod1 { |
26 |
| - public static final int angleMotorID = 22; |
27 |
| - public static final int canCoderID = 20; |
28 |
| - public static final Rotation2d angleOffset = Rotation2d.fromDegrees(272.285); |
29 |
| - } |
30 |
| - |
31 |
| - /* Back Left Module - Module 2 */ |
32 |
| - public static final class Mod2 { |
33 |
| - public static final int angleMotorID = 32; |
34 |
| - public static final int canCoderID = 30; |
35 |
| - public static final Rotation2d angleOffset = Rotation2d.fromDegrees(248.906); |
| 26 | + public ModConfig(int angleMotorID, int canCoderID, Rotation2d canCoderOffset) { |
| 27 | + m_angleMotorID = angleMotorID; |
| 28 | + m_canCoderID = canCoderID; |
| 29 | + m_canCoderOffset = canCoderOffset; |
36 | 30 | }
|
| 31 | + } |
37 | 32 |
|
38 |
| - /* Back Right Module - Module 3 */ |
39 |
| - public static final class Mod3 { |
40 |
| - public static final int angleMotorID = 42; |
41 |
| - public static final int canCoderID = 40; |
42 |
| - public static final Rotation2d angleOffset = Rotation2d.fromDegrees(92.461); |
43 |
| - } |
| 33 | + public static final ModConfig[] m_modConfigs = |
| 34 | + new ModConfig[] { |
| 35 | + new ModConfig(12, 10, Rotation2d.fromDegrees(117.334)), |
| 36 | + new ModConfig(22, 20, Rotation2d.fromDegrees(272.285)), |
| 37 | + new ModConfig(32, 30, Rotation2d.fromDegrees(248.906)), |
| 38 | + new ModConfig(42, 40, Rotation2d.fromDegrees(92.461)), |
| 39 | + }; |
44 | 40 |
|
45 |
| - public AngleMotorControl() { |
46 |
| - motor[0] = new TalonFX(Mod0.angleMotorID); |
47 |
| - motor[1] = new TalonFX(Mod1.angleMotorID); |
48 |
| - motor[2] = new TalonFX(Mod2.angleMotorID); |
49 |
| - motor[3] = new TalonFX(Mod3.angleMotorID); |
| 41 | + public static final TalonFX[] m_angleMotors = |
| 42 | + new TalonFX[] { |
| 43 | + new TalonFX(m_modConfigs[0].m_angleMotorID), |
| 44 | + new TalonFX(m_modConfigs[1].m_angleMotorID), |
| 45 | + new TalonFX(m_modConfigs[2].m_angleMotorID), |
| 46 | + new TalonFX(m_modConfigs[3].m_angleMotorID), |
| 47 | + }; |
50 | 48 |
|
51 |
| - CANcoder[0] = new CANcoder(Mod0.canCoderID); |
52 |
| - CANcoder[1] = new CANcoder(Mod1.canCoderID); |
53 |
| - CANcoder[2] = new CANcoder(Mod2.canCoderID); |
54 |
| - CANcoder[3] = new CANcoder(Mod3.canCoderID); |
| 49 | + public static final CANcoder[] m_canCoders = |
| 50 | + new CANcoder[] { |
| 51 | + new CANcoder(m_modConfigs[0].m_canCoderID), |
| 52 | + new CANcoder(m_modConfigs[1].m_canCoderID), |
| 53 | + new CANcoder(m_modConfigs[2].m_canCoderID), |
| 54 | + new CANcoder(m_modConfigs[3].m_canCoderID), |
| 55 | + }; |
55 | 56 |
|
56 |
| - resetAnglePos(); |
57 |
| - } |
58 |
| - public void resetAnglePos() { |
59 |
| - motor[0].setPosition( |
60 |
| - (Rotation2d.fromRotations(CANcoder[0].getAbsolutePosition().getValueAsDouble()).getDegrees() |
61 |
| - - Mod0.angleOffset.getDegrees())/ 360); |
62 |
| - motor[1].setPosition( |
63 |
| - (Rotation2d.fromRotations(CANcoder[1].getAbsolutePosition().getValueAsDouble()).getDegrees() |
64 |
| - - Mod0.angleOffset.getDegrees())/ 360); |
65 |
| - motor[2].setPosition( |
66 |
| - (Rotation2d.fromRotations(CANcoder[2].getAbsolutePosition().getValueAsDouble()).getDegrees() |
67 |
| - - Mod0.angleOffset.getDegrees())/ 360); |
68 |
| - motor[3].setPosition( |
69 |
| - (Rotation2d.fromRotations(CANcoder[3].getAbsolutePosition().getValueAsDouble()).getDegrees() |
70 |
| - - Mod0.angleOffset.getDegrees())/ 360); |
| 57 | + public AngleMotorControl() { |
| 58 | + TalonFXConfiguration angleMotorConfig = new TalonFXConfiguration(); |
| 59 | + |
| 60 | + angleMotorConfig.ClosedLoopGeneral.ContinuousWrap = true; |
| 61 | + angleMotorConfig.Feedback.SensorToMechanismRatio = 150.0 / 7.0; |
| 62 | + angleMotorConfig.MotionMagic.MotionMagicAcceleration = 1.0; |
| 63 | + angleMotorConfig.MotionMagic.MotionMagicCruiseVelocity = 1.0; |
| 64 | + angleMotorConfig.MotionMagic.MotionMagicExpo_kA = 0.17079; |
| 65 | + angleMotorConfig.MotionMagic.MotionMagicExpo_kV = 2.314285; |
| 66 | + angleMotorConfig.MotionMagic.MotionMagicJerk = 1.0; |
| 67 | + angleMotorConfig.Slot0.kS = 0.16992; |
| 68 | + angleMotorConfig.Slot0.kV = 2.314285; |
| 69 | + angleMotorConfig.Slot0.kA = 0.17079; |
| 70 | + angleMotorConfig.Slot0.kP = 107.142857; |
| 71 | + angleMotorConfig.Slot0.kI = 1.0; |
| 72 | + angleMotorConfig.Slot0.kD = 1.0; |
| 73 | + angleMotorConfig.MotorOutput.Inverted = InvertedValue.Clockwise_Positive; |
| 74 | + angleMotorConfig.MotorOutput.NeutralMode = NeutralModeValue.Coast; |
| 75 | + |
| 76 | + CANcoderConfiguration canCoderConfig = new CANcoderConfiguration(); |
| 77 | + |
| 78 | + canCoderConfig.MagnetSensor.AbsoluteSensorRange = AbsoluteSensorRangeValue.Signed_PlusMinusHalf; |
| 79 | + canCoderConfig.MagnetSensor.SensorDirection = SensorDirectionValue.Clockwise_Positive; |
| 80 | + |
| 81 | + for (int modIdx = 0; modIdx < m_modConfigs.length; modIdx++) { |
| 82 | + canCoderConfig.MagnetSensor.MagnetOffset = |
| 83 | + m_modConfigs[modIdx].m_canCoderOffset.getRotations(); |
| 84 | + m_angleMotors[modIdx].getConfigurator().apply(angleMotorConfig); |
| 85 | + m_canCoders[modIdx].getConfigurator().apply(canCoderConfig); |
| 86 | + m_angleMotors[modIdx].setPosition(m_canCoders[modIdx].getPosition().refresh().getValue()); |
71 | 87 | }
|
72 |
| - public static void periodic() { |
73 |
| - for (TalonFX F : motor) { |
74 |
| - PositionDutyCycle mRequest = new PositionDutyCycle(0); |
75 |
| - F.setControl(mRequest); |
76 |
| - } |
| 88 | + } |
| 89 | + |
| 90 | + public static void periodic() { |
| 91 | + for (TalonFX angleMotor : m_angleMotors) { |
| 92 | + angleMotor.setControl(new MotionMagicExpoVoltage(0)); |
77 | 93 | }
|
| 94 | + } |
78 | 95 | }
|
0 commit comments