Skip to content

Commit

Permalink
one final sonarqube thing
Browse files Browse the repository at this point in the history
  • Loading branch information
GearBoxFox committed Jan 21, 2024
1 parent b5ad9b7 commit b7bbc68
Show file tree
Hide file tree
Showing 3 changed files with 12 additions and 6 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -125,7 +125,8 @@ public ModuleIOSparkMax(int index) {
@Override
public void updateInputs(ModuleIOInputs inputs) {
inputs.setDrivePositionRad(Units.rotationsToRadians(driveEncoder.getPosition()) / DRIVE_GEAR_RATIO);
inputs.setDriveVelocityRadPerSec(Units.rotationsPerMinuteToRadiansPerSecond(driveEncoder.getVelocity()) / DRIVE_GEAR_RATIO);
inputs.setDriveVelocityRadPerSec(
Units.rotationsPerMinuteToRadiansPerSecond(driveEncoder.getVelocity()) / DRIVE_GEAR_RATIO);
inputs.setDriveAppliedVolts(driveSparkMax.getAppliedOutput() * driveSparkMax.getBusVoltage());
inputs.setDriveCurrentAmps(new double[] {driveSparkMax.getOutputCurrent()});

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -168,15 +168,19 @@ public void updateInputs(ModuleIOInputs inputs) {
m_turnAppliedVolts,
m_turnCurrent);

inputs.setDrivePositionRad(Units.rotationsToRadians(m_drivePosition.getValueAsDouble()) / m_moduleConstants.DRIVE_GEAR_RATIO());
inputs.setDriveVelocityRadPerSec(Units.rotationsToRadians(m_driveVelocity.getValueAsDouble()) / m_moduleConstants.DRIVE_GEAR_RATIO());
inputs.setDrivePositionRad(
Units.rotationsToRadians(m_drivePosition.getValueAsDouble()) / m_moduleConstants.DRIVE_GEAR_RATIO());
inputs.setDriveVelocityRadPerSec(
Units.rotationsToRadians(m_driveVelocity.getValueAsDouble()) / m_moduleConstants.DRIVE_GEAR_RATIO());
inputs.setDriveAppliedVolts(m_driveAppliedVolts.getValueAsDouble());
inputs.setDriveCurrentAmps(new double[] {m_driveCurrent.getValueAsDouble()});

inputs.setTurnAbsolutePosition(Rotation2d.fromRotations(m_turnAbsolutePosition.getValueAsDouble())
.minus(m_moduleConstants.ENCODER_OFFSET()));
inputs.setTurnPosition(Rotation2d.fromRotations((m_turnPosition.getValueAsDouble() / m_moduleConstants.TURNING_GEAR_RATIO())));
inputs.setTurnVelocityRadPerSec(Units.rotationsToRadians(m_turnVelocity.getValueAsDouble()) / m_moduleConstants.TURNING_GEAR_RATIO());
inputs.setTurnPosition(Rotation2d.fromRotations((
m_turnPosition.getValueAsDouble() / m_moduleConstants.TURNING_GEAR_RATIO())));
inputs.setTurnVelocityRadPerSec(
Units.rotationsToRadians(m_turnVelocity.getValueAsDouble()) / m_moduleConstants.TURNING_GEAR_RATIO());
inputs.setTurnAppliedVolts(m_turnAppliedVolts.getValueAsDouble());
inputs.setTurnCurrentAmps(new double[] {m_turnCurrent.getValueAsDouble()});

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
import com.ctre.phoenix6.CANBus;
import com.ctre.phoenix6.StatusSignal;
import com.ctre.phoenix6.hardware.ParentDevice;
import edu.wpi.first.wpilibj.DriverStation;
import frc.robot.subsystems.drive.DriveSubsystem;

import java.util.ArrayList;
Expand Down Expand Up @@ -93,7 +94,7 @@ public void run() {
}
}
} catch (InterruptedException e) {
e.printStackTrace();
DriverStation.reportError(e.toString(), true);
} finally {
signalsLock.unlock();
}
Expand Down

0 comments on commit b7bbc68

Please sign in to comment.