Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

0.02 changed to loopPeriodSecs #21

Merged
merged 1 commit into from
Feb 17, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion src/main/java/org/littletonrobotics/frc2024/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
* constants are needed, to reduce verbosity.
*/
public final class Constants {
public static final int loopPeriodMs = 20;
public static final double loopPeriodSecs = 0.02;
private static RobotType robotType = RobotType.DEVBOT;
public static final boolean tuningMode = true;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
import java.util.concurrent.locks.ReentrantLock;
import java.util.stream.IntStream;
import lombok.experimental.ExtensionMethod;
import org.littletonrobotics.frc2024.Constants;
import org.littletonrobotics.frc2024.RobotState;
import org.littletonrobotics.frc2024.subsystems.drive.controllers.AutoAimController;
import org.littletonrobotics.frc2024.subsystems.drive.controllers.AutoAlignController;
Expand Down Expand Up @@ -255,7 +256,7 @@ public void periodic() {
// Generate feasible next setpoint
currentSetpoint =
setpointGenerator.generateSetpoint(
currentModuleLimits, currentSetpoint, desiredSpeeds, 0.02);
currentModuleLimits, currentSetpoint, desiredSpeeds, Constants.loopPeriodSecs);
// run modules
SwerveModuleState[] optimizedSetpointStates = new SwerveModuleState[4];
for (int i = 0; i < modules.length; i++) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,15 +14,18 @@
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.system.plant.DCMotor;
import edu.wpi.first.wpilibj.simulation.DCMotorSim;
import org.littletonrobotics.frc2024.Constants;

public class ModuleIOSim implements ModuleIO {
private final DCMotorSim driveSim =
new DCMotorSim(DCMotor.getKrakenX60Foc(1), moduleConstants.driveReduction(), 0.025);
private final DCMotorSim turnSim =
new DCMotorSim(DCMotor.getKrakenX60Foc(1), moduleConstants.turnReduction(), 0.004);

private final PIDController driveFeedback = new PIDController(0.0, 0.0, 0.0, 0.02);
private final PIDController turnFeedback = new PIDController(0.0, 0.0, 0.0, 0.02);
private final PIDController driveFeedback =
new PIDController(0.0, 0.0, 0.0, Constants.loopPeriodSecs);
private final PIDController turnFeedback =
new PIDController(0.0, 0.0, 0.0, Constants.loopPeriodSecs);

private double driveAppliedVolts = 0.0;
private double turnAppliedVolts = 0.0;
Expand All @@ -35,8 +38,8 @@ public ModuleIOSim(ModuleConfig config) {

@Override
public void updateInputs(ModuleIOInputs inputs) {
driveSim.update(0.02);
turnSim.update(0.02);
driveSim.update(Constants.loopPeriodSecs);
turnSim.update(Constants.loopPeriodSecs);

inputs.drivePositionRad = driveSim.getAngularPositionRad();
inputs.driveVelocityRadPerSec = driveSim.getAngularVelocityRadPerSec();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@

import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.util.Units;
import org.littletonrobotics.frc2024.Constants;
import org.littletonrobotics.frc2024.RobotState;
import org.littletonrobotics.frc2024.subsystems.drive.DriveConstants;
import org.littletonrobotics.frc2024.util.LoggedTunableNumber;
Expand All @@ -26,7 +27,7 @@ public class AutoAimController {
private PIDController headingController;

public AutoAimController() {
headingController = new PIDController(0, 0, 0, 0.02);
headingController = new PIDController(0, 0, 0, Constants.loopPeriodSecs);
headingController.enableContinuousInput(-Math.PI, Math.PI);
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
import edu.wpi.first.math.system.plant.DCMotor;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.simulation.FlywheelSim;
import org.littletonrobotics.frc2024.Constants;

public class FlywheelsIOSim implements FlywheelsIO {
private final FlywheelSim leftSim =
Expand All @@ -37,8 +38,8 @@ public class FlywheelsIOSim implements FlywheelsIO {

@Override
public void updateInputs(FlywheelsIOInputs inputs) {
leftSim.update(0.02);
rightSim.update(0.02);
leftSim.update(Constants.loopPeriodSecs);
rightSim.update(Constants.loopPeriodSecs);
// control to setpoint
if (leftSetpointRPM != null && rightSetpointRPM != null) {
runVolts(
Expand All @@ -49,13 +50,13 @@ public void updateInputs(FlywheelsIOInputs inputs) {
}

inputs.leftPositionRads +=
Units.radiansToRotations(leftSim.getAngularVelocityRadPerSec() * 0.02);
Units.radiansToRotations(leftSim.getAngularVelocityRadPerSec() * Constants.loopPeriodSecs);
inputs.leftVelocityRpm = leftSim.getAngularVelocityRPM();
inputs.leftAppliedVolts = leftAppliedVolts;
inputs.leftOutputCurrent = leftSim.getCurrentDrawAmps();

inputs.rightPositionRads +=
Units.radiansToRotations(rightSim.getAngularVelocityRadPerSec() * 0.02);
Units.radiansToRotations(rightSim.getAngularVelocityRadPerSec() * Constants.loopPeriodSecs);
inputs.rightVelocityRpm = rightSim.getAngularVelocityRPM();
inputs.rightAppliedVolts = rightAppliedVolts;
inputs.rightOutputCurrent = rightSim.getCurrentDrawAmps();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@
import edu.wpi.first.math.system.plant.DCMotor;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.simulation.DCMotorSim;
import org.littletonrobotics.frc2024.Constants;

public class GenericRollerSystemIOSim implements GenericRollerSystemIO {
private final DCMotorSim sim;
Expand All @@ -26,7 +27,7 @@ public void updateInputs(GenericRollerSystemIOInputs inputs) {
runVolts(0.0);
}

sim.update(0.02);
sim.update(Constants.loopPeriodSecs);
inputs.positionRads = sim.getAngularPositionRad();
inputs.velocityRadsPerSec = sim.getAngularVelocityRadPerSec();
inputs.appliedVoltage = appliedVoltage;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
import lombok.Getter;
import lombok.RequiredArgsConstructor;
import lombok.Setter;
import org.littletonrobotics.frc2024.Constants;
import org.littletonrobotics.frc2024.RobotState;
import org.littletonrobotics.frc2024.util.EqualsUtil;
import org.littletonrobotics.frc2024.util.LoggedTunableNumber;
Expand Down Expand Up @@ -122,7 +123,7 @@ public void periodic() {
// Run closed loop
setpointState =
motionProfile.calculate(
0.02,
Constants.loopPeriodSecs,
new TrapezoidProfile.State(inputs.armPositionRads, inputs.armVelocityRadsPerSec),
new TrapezoidProfile.State(
MathUtil.clamp(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.simulation.SingleJointedArmSim;
import org.littletonrobotics.frc2024.Constants;

public class ArmIOSim implements ArmIO {
private final SingleJointedArmSim sim =
Expand Down Expand Up @@ -47,7 +48,7 @@ public void updateInputs(ArmIOInputs inputs) {
controllerNeedsReset = true;
}

sim.update(0.02);
sim.update(Constants.loopPeriodSecs);

inputs.armPositionRads = sim.getAngleRads() + positionOffset;
inputs.armVelocityRadsPerSec = sim.getVelocityRadPerSec();
Expand Down
Loading