Skip to content
This repository has been archived by the owner on May 19, 2024. It is now read-only.

Commit

Permalink
fix(swerve): Use steer PIDF for simulated steer motor.
Browse files Browse the repository at this point in the history
  • Loading branch information
haydenheroux committed Jan 19, 2024
1 parent 93a615e commit 7ed98e2
Show file tree
Hide file tree
Showing 2 changed files with 24 additions and 10 deletions.
10 changes: 6 additions & 4 deletions simgui.json
Original file line number Diff line number Diff line change
Expand Up @@ -15,10 +15,13 @@
"NetworkTables": {
"transitory": {
"Shuffleboard": {
"Swerve": {
"Module 0": {
"Odometry": {
"Velocity": {
"open": true
},
"open": true
},
"Swerve": {
"Module 1": {
"open": true
},
Expand All @@ -30,8 +33,7 @@
},
"North East Module": {
"open": true
},
"open": true
}
},
"open": true
},
Expand Down
24 changes: 18 additions & 6 deletions src/main/java/frc/robot/swerve/SteerMotorIOSim.java
Original file line number Diff line number Diff line change
@@ -1,9 +1,10 @@
package frc.robot.swerve;

import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.system.plant.DCMotor;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.simulation.FlywheelSim;
import frc.lib.PIDFConstants;
import frc.robot.RobotConstants;
import frc.robot.swerve.SwerveConstants.MK4iConstants;

Expand All @@ -23,15 +24,23 @@ public class SteerMotorIOSim implements SteerMotorIO {
/** Represents the velocity of the steer motor. */
private double velocityRotationsPerSecond;

/** Feedback controller for the position. */
// TODO
private final PIDController positionFeedback = new PIDController(1.0, 0, 0.25);
/** Constants for PIDF position controller. */
private static PIDFConstants pidfConstants = new PIDFConstants();

static {
pidfConstants.kP = 1.0; // volts per rotation
pidfConstants.kVelocityConstraint = 10.0; // volts per rotation per second
pidfConstants.kAccelerationConstraint = 64.0; // volts per rotation per second per second
}

/** PIDF position controller. */
private final SteerMotorPIDF pidf;

public SteerMotorIOSim() {
positionRotations = 0.0;
velocityRotationsPerSecond = 0.0;

positionFeedback.enableContinuousInput(0, 1);
pidf = new SteerMotorPIDF(pidfConstants);
}

@Override
Expand All @@ -50,7 +59,10 @@ public void setPosition(double positionRotations) {

@Override
public void setSetpoint(double positionRotations) {
double voltage = positionFeedback.calculate(this.positionRotations, positionRotations);
double voltage =
pidf.calculate(
Rotation2d.fromRotations(this.positionRotations),
Rotation2d.fromRotations(positionRotations));

wheelSim.setInputVoltage(voltage);
wheelSim.update(RobotConstants.PERIODIC_DURATION);
Expand Down

0 comments on commit 7ed98e2

Please sign in to comment.