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

Motor sim control loops #32

Merged
merged 50 commits into from
Nov 19, 2024
Merged

Motor sim control loops #32

merged 50 commits into from
Nov 19, 2024

Conversation

catr1xLiu
Copy link
Contributor

Hardware Control Loops Simulation for MapleMotorSim

GearBoxFox and others added 30 commits November 5, 2024 07:58
# Conflicts:
#	project/src/main/java/org/ironmaple/simulation/drivesims/SimplifiedSwerveDriveSimulation.java
# Conflicts:
#	.gitignore
#	project/src/main/java/org/ironmaple/simulation/MapleMotorSim.java
#	project/src/main/java/org/ironmaple/simulation/drivesims/SimplifiedSwerveDriveSimulation.java
#	project/src/main/java/org/ironmaple/simulation/drivesims/SwerveModuleSimulation.java
Using hardware close loop simulation in simplified swerve sim
Conversion to WPILib Units
used wpilib units for configurations
@catr1xLiu catr1xLiu changed the base branch from main to dev November 11, 2024 06:10
public final Torque friction;

/* all these controllers receive un-geared position/velocity from the encoder, not the final position/velocity of the mechanism */
public final PIDController positionVoltageController;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Do the PID controllers themselves have to be in the config. I feel like that's greatly expanding the scope of what a config is.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

technically ur right, but it saves maplemotorsim from beeing like 600lines because of all the "with" methods

so, yeah, I guess it's no harm


import edu.wpi.first.units.measure.*;

public record SimMotorState(Angle finalAngularPosition, AngularVelocity finalAngularVelocity) {
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Does this have to be in wpilib units? it may make it easier moving all stuff not exposed to the user back to doubles.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I also thought that the wpilib units syntax isn't great for computation and therefore shouldn't be used for internal variables
but so far it's been working better than what I expect, I guess I'll give it a try in maple motor sim


public sealed interface ControlRequest
permits CurrentOut, PositionCurrent, PositionVoltage, VelocityCurrent, VelocityVoltage, VoltageOut {
Voltage updateSignal(SimMotorConfigs configs, Angle encoderPosition, AngularVelocity encoderVelocity);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The control request taking the config and not the motor itself greatly limits what it can do, I could see the argument for limiting miss-use by restricting what they have access to but the motors don't really have any scenario breaking methods.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

ur right on that

the only concern I have is future contributors will directly call to MapleMotorSim.requestOutput(new VoltageOut(...)) in the updateSignal() method to pass the applied volts

I guess I should warn people, in the javadocs of ControlRequest inerface, to not do that?

@@ -304,19 +295,6 @@ public void simulationPeriodic() {
* </ul>
*/
private void simulationSubTick() {
ArrayList<Double> motorCurrents = new ArrayList<>();
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

If we intend for users to use the motor sims themselves I believe it would be beneficial if we handle the polling, higher hz running on the PID loops makes them respond closer to real life aswell.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

NP, I'll have all maple motor sims updated in simulated arena subtick

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

hold on, I thought they should be updated in SimRobot, where the current drawn are also sent to the battery simulation

this.reverseHardwareLimit = Radians.of(Double.NEGATIVE_INFINITY);
this.currentLimit = Amps.of(150);

this.withFeedForward(
Copy link
Contributor

@oh-yes-0-fps oh-yes-0-fps Nov 11, 2024

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I still stand by the fact the motor sim shouldn't do FeedForward for you, it could cause the motor to behave differently than a real motor without a good explanation why if the user didn't configure feed forward on the real motor. Adding this code to the javadoc of withFeedForward could be a good alternative to show the user what they could do easily.

Another note is that the MOI, gearing and motor are enough to figure out kA aswell :)

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

NP! I'll move this code to the javadocs of SimMotorConfigs class instead.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Not good at math but I think it's

kA = nomical voltage / (stall torque * gear ratio / MOI)

is that correct?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

end up having this

    /**
     * <h2>Configures a default set of feedforward gains.</h2>
     *
     * <p>The feedforward gains (ks, kv, and ka) will be calculated using the data of the{@link DCMotor} model.</p>
     *
     * @return this instance for method changing
     * */
    public SimMotorConfigs withDefaultFeedForward() {
        return this.withFeedForward(
                this.calculateVoltage(calculateCurrent(friction), RadiansPerSecond.zero()),
                VoltsPerRadianPerSecond.ofNative(motor.nominalVoltageVolts / motor.freeSpeedRadPerSec),
                VoltsPerRadianPerSecondSquared.ofNative(
                        motor.nominalVoltageVolts / (motor.stallTorqueNewtonMeters / this.loadMOI.in(KilogramSquareMeters))
                ),
                Seconds.of(SimulatedArena.getSimulationDt()));
    }

@catr1xLiu catr1xLiu marked this pull request as ready for review November 19, 2024 07:53
@catr1xLiu catr1xLiu merged commit 72e2d7d into dev Nov 19, 2024
@catr1xLiu catr1xLiu deleted the motor-sim-control-loops branch November 19, 2024 07:55
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

4 participants