Skip to content

Commit

Permalink
minor updates for module.java and gyroiopigeon2
Browse files Browse the repository at this point in the history
  • Loading branch information
GearBoxFox committed Jan 20, 2024
1 parent 79c20aa commit 009d44a
Show file tree
Hide file tree
Showing 2 changed files with 17 additions and 19 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ public void updateInputs(GyroIOInputs inputs) {

inputs.odometryYawPositions =
yawPositionQueue.stream()
.map((Double value) -> Rotation2d.fromDegrees(value))
.map(Rotation2d::fromDegrees)
.toArray(Rotation2d[]::new);
yawPositionQueue.clear();
}
Expand Down
34 changes: 16 additions & 18 deletions src/main/java/frc/robot/subsystems/drive/module/Module.java
Original file line number Diff line number Diff line change
Expand Up @@ -18,10 +18,8 @@
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.kinematics.SwerveModulePosition;
import edu.wpi.first.math.kinematics.SwerveModuleState;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.Timer;
import frc.robot.Constants;
import org.littletonrobotics.junction.AutoLogOutput;
import org.littletonrobotics.junction.Logger;

public class Module {
Expand Down Expand Up @@ -51,22 +49,22 @@ public Module(ModuleIO io) {

// Switch constants based on mode (the physics simulator is treated as a
// separate robot with different tuning)
switch (Constants.currentMode) {
case REAL, REPLAY -> {
m_driveFeedforward = new SimpleMotorFeedforward(0.1, 0.13);
m_driveFeedback = new PIDController(0.05, 0.0, 0.0);
m_turnFeedback = new PIDController(7.0, 0.0, 0.0);
}
case SIM -> {
m_driveFeedforward = new SimpleMotorFeedforward(0.0, 0.13);
m_driveFeedback = new PIDController(0.1, 0.0, 0.0);
m_turnFeedback = new PIDController(10.0, 0.0, 0.0);
}
default -> {
m_driveFeedforward = new SimpleMotorFeedforward(0.0, 0.0);
m_driveFeedback = new PIDController(0.0, 0.0, 0.0);
m_turnFeedback = new PIDController(0.0, 0.0, 0.0);
}
switch (Constants.currentMode) {
case REAL, REPLAY -> {
m_driveFeedforward = new SimpleMotorFeedforward(0.1, 0.13);
m_driveFeedback = new PIDController(0.05, 0.0, 0.0);
m_turnFeedback = new PIDController(7.0, 0.0, 0.0);
}
case SIM -> {
m_driveFeedforward = new SimpleMotorFeedforward(0.0, 0.13);
m_driveFeedback = new PIDController(0.1, 0.0, 0.0);
m_turnFeedback = new PIDController(10.0, 0.0, 0.0);
}
default -> {
m_driveFeedforward = new SimpleMotorFeedforward(0.0, 0.0);
m_driveFeedback = new PIDController(0.0, 0.0, 0.0);
m_turnFeedback = new PIDController(0.0, 0.0, 0.0);
}
}

m_turnFeedback.enableContinuousInput(-Math.PI, Math.PI);
Expand Down

0 comments on commit 009d44a

Please sign in to comment.