Skip to content

Commit

Permalink
redux
Browse files Browse the repository at this point in the history
  • Loading branch information
indoorfish1 committed Jan 5, 2025
1 parent c51d278 commit 1068a32
Show file tree
Hide file tree
Showing 4 changed files with 26 additions and 31 deletions.
2 changes: 1 addition & 1 deletion .wpilib/wpilib_preferences.json
Original file line number Diff line number Diff line change
Expand Up @@ -2,5 +2,5 @@
"enableCppIntellisense": false,
"currentLanguage": "java",
"projectYear": "2024",
"teamNumber": 9990
"teamNumber": 4930
}
1 change: 0 additions & 1 deletion src/main/java/frc/robot/subsystems/drive/GyroIO.java
Original file line number Diff line number Diff line change
Expand Up @@ -23,5 +23,4 @@ class GyroIOInputs {
}

default void resetIMU() {}

}
52 changes: 24 additions & 28 deletions src/main/java/frc/robot/subsystems/drive/GyroIORedux.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,38 +2,34 @@

import com.reduxrobotics.sensors.canandgyro.Canandgyro;

/**
* Hardware interface for the Reduxrobotics Can-and-gyro IMU
*/
/** Hardware interface for the Reduxrobotics Can-and-gyro IMU */
public class GyroIORedux implements GyroIO {
private final Canandgyro gyro;
private final Canandgyro gyro;

/**
* Creates a new gyro, with period 0.02 on yaw updates, and 0.1 on status updates.
*/
public GyroIORedux() {
gyro = new Canandgyro(50);
gyro.clearStickyFaults();
gyro.setPartyMode(0);
/** Creates a new gyro, with period 0.02 on yaw updates, and 0.1 on status updates. */
public GyroIORedux() {
gyro = new Canandgyro(50);
gyro.clearStickyFaults();
gyro.setPartyMode(0);

Canandgyro.Settings settings = new Canandgyro.Settings();
settings.setAngularPositionFramePeriod(0.02); //20ms update
settings.setYawFramePeriod(0.02);
settings.setStatusFramePeriod(0.1);
Canandgyro.Settings settings = new Canandgyro.Settings();
settings.setAngularPositionFramePeriod(0.02); // 20ms update
settings.setYawFramePeriod(0.02);
settings.setStatusFramePeriod(0.1);

gyro.setSettings(settings,0.050);
}
gyro.setSettings(settings, 0.050);
}

@Override
public void updateInputs(GyroIOInputs inputs) {
inputs.connected = gyro.isConnected();
inputs.yawPositionRad = -Math.toRadians(gyro.getYaw());
inputs.yawVelocityRadPerSec = -Math.toRadians(gyro.getAngularVelocityYaw());
}
@Override
public void updateInputs(GyroIOInputs inputs) {
inputs.connected = gyro.isConnected();
inputs.yawPositionRad = -Math.toRadians(gyro.getYaw());
inputs.yawVelocityRadPerSec = -Math.toRadians(gyro.getAngularVelocityYaw());
}

@Override
public void resetIMU() {
System.out.println("resetting IMU");
gyro.setYaw(0);
}
@Override
public void resetIMU() {
System.out.println("resetting IMU");
gyro.setYaw(0);
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ public IndexerIOReal() {
var config = new TalonFXConfiguration();
config.CurrentLimits.StatorCurrentLimit = Constants.IndexerConstants.INDEX_CURRENT_LIMIT;
config.CurrentLimits.StatorCurrentLimitEnable = true;
config.MotorOutput.Inverted = InvertedValue.CounterClockwise_Positive; // TODO: check
config.MotorOutput.Inverted = InvertedValue.CounterClockwise_Positive;
config.MotorOutput.NeutralMode = NeutralModeValue.Coast;
indexerMotor.getConfigurator().apply(config);
}
Expand Down

0 comments on commit 1068a32

Please sign in to comment.