Skip to content

Commit

Permalink
fix: swerve motor current is no longer logged as an array
Browse files Browse the repository at this point in the history
  • Loading branch information
mimizh2418 committed Jan 15, 2024
1 parent d7cd339 commit e43532d
Show file tree
Hide file tree
Showing 3 changed files with 6 additions and 6 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -9,13 +9,13 @@ class ModuleIOInputs {
public double drivePositionRad = 0.0;
public double driveVelocityRadPerSec = 0.0;
public double driveAppliedVolts = 0.0;
public double[] driveCurrentAmps = new double[]{};
public double driveCurrentAmps = 0.0;

public Rotation2d turnAbsolutePosition = new Rotation2d();
public Rotation2d turnPosition = new Rotation2d();
public double turnVelocityRadPerSec = 0.0;
public double turnAppliedVolts = 0.0;
public double[] turnCurrentAmps = new double[]{};
public double turnCurrentAmps = 0.0;
}

/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,13 +28,13 @@ public void updateInputs(ModuleIOInputs inputs) {
inputs.drivePositionRad = driveSim.getAngularPositionRad();
inputs.driveVelocityRadPerSec = driveSim.getAngularVelocityRadPerSec();
inputs.driveAppliedVolts = driveAppliedVolts;
inputs.driveCurrentAmps = new double[]{Math.abs(driveSim.getCurrentDrawAmps())};
inputs.driveCurrentAmps = Math.abs(driveSim.getCurrentDrawAmps());

inputs.turnAbsolutePosition = new Rotation2d(turnSim.getAngularPositionRad()).plus(turnAbsoluteInitPosition);
inputs.turnPosition = new Rotation2d(turnSim.getAngularPositionRad());
inputs.turnVelocityRadPerSec = turnSim.getAngularVelocityRadPerSec();
inputs.turnAppliedVolts = turnAppliedVolts;
inputs.turnCurrentAmps = new double[]{Math.abs(turnSim.getCurrentDrawAmps())};
inputs.turnCurrentAmps = Math.abs(turnSim.getCurrentDrawAmps());
}

@Override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -77,13 +77,13 @@ public void updateInputs(ModuleIOInputs inputs) {
inputs.drivePositionRad = Units.rotationsToRadians(drivePosition.getValueAsDouble()) / Constants.Drivetrain.DRIVE_GEAR_RATIO;
inputs.driveVelocityRadPerSec = Units.rotationsToRadians(driveVelocity.getValueAsDouble()) / Constants.Drivetrain.DRIVE_GEAR_RATIO;
inputs.driveAppliedVolts = driveAppliedVolts.getValueAsDouble();
inputs.driveCurrentAmps = new double[]{driveCurrent.getValueAsDouble()};
inputs.driveCurrentAmps = driveCurrent.getValueAsDouble();

inputs.turnAbsolutePosition = Rotation2d.fromRotations(turnAbsolutePosition.getValueAsDouble()).plus(absoluteEncoderOffset);
inputs.turnPosition = Rotation2d.fromRotations(turnPosition.getValueAsDouble() / Constants.Drivetrain.TURN_GEAR_RATIO);
inputs.turnVelocityRadPerSec = Units.rotationsToRadians(turnVelocity.getValueAsDouble()) / Constants.Drivetrain.TURN_GEAR_RATIO;
inputs.turnAppliedVolts = turnAppliedVolts.getValueAsDouble();
inputs.turnCurrentAmps = new double[]{turnCurrent.getValueAsDouble()};
inputs.turnCurrentAmps = turnCurrent.getValueAsDouble();
}

@Override
Expand Down

0 comments on commit e43532d

Please sign in to comment.