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

Commit

Permalink
fix: Change gear ratios.
Browse files Browse the repository at this point in the history
  • Loading branch information
haydenheroux committed Apr 2, 2024
1 parent 2dd37bb commit a65a257
Show file tree
Hide file tree
Showing 5 changed files with 41 additions and 9 deletions.
2 changes: 1 addition & 1 deletion simgui-ds.json
Original file line number Diff line number Diff line change
Expand Up @@ -98,10 +98,10 @@
],
"robotJoysticks": [
{
"guid": "78696e70757401000000000000000000",
"useGamepad": true
},
{
"guid": "78696e70757401000000000000000000",
"useGamepad": true
}
]
Expand Down
30 changes: 23 additions & 7 deletions src/main/java/frc/robot/arm/ShoulderMotorIOTalonFX.java
Original file line number Diff line number Diff line change
@@ -1,9 +1,13 @@
package frc.robot.arm;

import com.ctre.phoenix6.configs.CANcoderConfiguration;
import com.ctre.phoenix6.configs.TalonFXConfiguration;
import com.ctre.phoenix6.hardware.CANcoder;
import com.ctre.phoenix6.hardware.TalonFX;
import com.ctre.phoenix6.signals.InvertedValue;
import com.ctre.phoenix6.signals.NeutralModeValue;
import com.ctre.phoenix6.signals.SensorDirectionValue;

import edu.wpi.first.math.controller.ArmFeedforward;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.util.Units;
Expand All @@ -14,6 +18,8 @@ public class ShoulderMotorIOTalonFX implements ShoulderMotorIO {

private final TalonFX eastTalonFX, westTalonFX;

private final CANcoder cancoder;

/** Feedback controller for shoulder position. */
private final PIDController feedback;

Expand All @@ -25,24 +31,34 @@ public ShoulderMotorIOTalonFX() {
eastTalonFX = new TalonFX(0); // TODO
westTalonFX = new TalonFX(0); // TODO

cancoder = new CANcoder(0); // TODO

feedback = new PIDController(0, 0, 0);

feedforward = new ArmFeedforward(0, 0, 0);
}

@Override
public void configure() {
final TalonFXConfiguration config = new TalonFXConfiguration();
final TalonFXConfiguration talonFXConfig = new TalonFXConfiguration();

// talonFXConfig.Feedback.SensorToMechanismRatio = 39.771428571;

talonFXConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake;

talonFXConfig.MotorOutput.Inverted = InvertedValue.Clockwise_Positive;
Configurator.configureTalonFX(eastTalonFX.getConfigurator(), talonFXConfig);

talonFXConfig.MotorOutput.Inverted = InvertedValue.CounterClockwise_Positive;
Configurator.configureTalonFX(westTalonFX.getConfigurator(), talonFXConfig);

config.Feedback.SensorToMechanismRatio = 1.0; // TODO
final CANcoderConfiguration cancoderConfig = new CANcoderConfiguration();

config.MotorOutput.NeutralMode = NeutralModeValue.Brake;
cancoderConfig.MagnetSensor.SensorDirection = SensorDirectionValue.Clockwise_Positive;

config.MotorOutput.Inverted = InvertedValue.Clockwise_Positive;
Configurator.configureTalonFX(eastTalonFX.getConfigurator(), config);
cancoderConfig.MagnetSensor.MagnetOffset = -0.0; // TODO

config.MotorOutput.Inverted = InvertedValue.CounterClockwise_Positive;
Configurator.configureTalonFX(westTalonFX.getConfigurator(), config);
Configurator.configureCANcoder(cancoder.getConfigurator(), cancoderConfig);
}

@Override
Expand Down
8 changes: 7 additions & 1 deletion src/main/java/frc/robot/intake/RollerMotorIOTalonFX.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@

import com.ctre.phoenix6.configs.TalonFXConfiguration;
import com.ctre.phoenix6.hardware.TalonFX;
import com.ctre.phoenix6.signals.InvertedValue;
import com.ctre.phoenix6.signals.NeutralModeValue;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import frc.lib.Configurator;
Expand All @@ -24,11 +25,16 @@ public RollerMotorIOTalonFX() {
public void configure() {
final TalonFXConfiguration config = new TalonFXConfiguration();

config.Feedback.SensorToMechanismRatio = 1.0; // TODO
config.Feedback.SensorToMechanismRatio = 24.0 / 16.0;

config.MotorOutput.NeutralMode = NeutralModeValue.Coast;

config.MotorOutput.Inverted = InvertedValue.Clockwise_Positive;

Configurator.configureTalonFX(topTalonFX.getConfigurator(), config);

config.MotorOutput.Inverted = InvertedValue.Clockwise_Positive;

Configurator.configureTalonFX(bottomTalonFX.getConfigurator(), config);
}

Expand Down
5 changes: 5 additions & 0 deletions src/main/java/frc/robot/shooter/FlywheelMotorIOTalonFX.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
import com.ctre.phoenix6.StatusSignal;
import com.ctre.phoenix6.configs.TalonFXConfiguration;
import com.ctre.phoenix6.hardware.TalonFX;
import com.ctre.phoenix6.signals.InvertedValue;
import com.ctre.phoenix6.signals.NeutralModeValue;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import frc.lib.Configurator;
Expand All @@ -29,8 +30,12 @@ public FlywheelMotorIOTalonFX() {
public void configure() {
final TalonFXConfiguration config = new TalonFXConfiguration();

config.Feedback.SensorToMechanismRatio = 36.0 / 16.0;

config.MotorOutput.NeutralMode = NeutralModeValue.Coast;

config.MotorOutput.Inverted = InvertedValue.Clockwise_Positive;

Configurator.configureTalonFX(talonFX.getConfigurator(), config);
}

Expand Down
5 changes: 5 additions & 0 deletions src/main/java/frc/robot/shooter/SerializerMotorIOTalonFX.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
import com.ctre.phoenix6.StatusSignal;
import com.ctre.phoenix6.configs.TalonFXConfiguration;
import com.ctre.phoenix6.hardware.TalonFX;
import com.ctre.phoenix6.signals.InvertedValue;
import com.ctre.phoenix6.signals.NeutralModeValue;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import frc.lib.Configurator;
Expand All @@ -29,8 +30,12 @@ public SerializerMotorIOTalonFX() {
public void configure() {
final TalonFXConfiguration config = new TalonFXConfiguration();

config.Feedback.SensorToMechanismRatio = 36.0 / 16.0;

config.MotorOutput.NeutralMode = NeutralModeValue.Coast;

config.MotorOutput.Inverted = InvertedValue.CounterClockwise_Positive;

Configurator.configureTalonFX(talonFX.getConfigurator(), config);
}

Expand Down

0 comments on commit a65a257

Please sign in to comment.