Skip to content

Commit

Permalink
Initial file setup with FlywheelSim
Browse files Browse the repository at this point in the history
  • Loading branch information
narmstro2020 committed Oct 3, 2024
1 parent f82e1c9 commit 1dff657
Show file tree
Hide file tree
Showing 3 changed files with 154 additions and 39 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -17,18 +17,17 @@
import edu.wpi.first.units.measure.AngularVelocity;
import edu.wpi.first.units.measure.MutAngularAcceleration;
import edu.wpi.first.units.measure.MutAngularVelocity;
import edu.wpi.first.wpilibj.RobotController;

/** Represents a simulated flywheel mechanism. */
public class FlywheelSim extends LinearSystemSim<N1, N1, N1> {
public abstract class FlywheelSim extends LinearSystemSim<N1, N1, N1> {
// Gearbox for the flywheel.
private final DCMotor m_gearbox;

// The gearing from the motors to the output.
private final double m_gearing;

// The moment of inertia for the flywheel mechanism.
private final double m_jKgMetersSquared;
final double m_jKgMetersSquared;

// The angular velocity of the system.
private final MutAngularVelocity m_angularVelocity = RadiansPerSecond.mutable(0);
Expand All @@ -39,35 +38,43 @@ public class FlywheelSim extends LinearSystemSim<N1, N1, N1> {
/**
* Creates a simulated flywheel mechanism.
*
* @param plant The linear system that represents the flywheel. Use either {@link
* LinearSystemId#createFlywheelSystem(DCMotor, double, double)} if using physical constants
* or {@link LinearSystemId#identifyVelocitySystem(double, double)} if using system
* characterization.
* @param gearbox The type of and number of motors in the flywheel gearbox.
* @param measurementStdDevs The standard deviations of the measurements. Can be omitted if no
* noise is desired. If present must have 1 element for velocity.
* @param plant The linear system that represents the flywheel. Use
* either {@link
* LinearSystemId#createFlywheelSystem(DCMotor, double, double)}
* if using physical constants
* or
* {@link LinearSystemId#identifyVelocitySystem(double, double)}
* if using system
* characterization.
* @param gearbox The type of and number of motors in the flywheel
* gearbox.
* @param measurementStdDevs The standard deviations of the measurements. Can be
* omitted if no
* noise is desired. If present must have 1 element
* for velocity.
*/
public FlywheelSim(
LinearSystem<N1, N1, N1> plant, DCMotor gearbox, double... measurementStdDevs) {
super(plant, measurementStdDevs);
m_gearbox = gearbox;

// By theorem 6.10.1 of https://file.tavsys.net/control/controls-engineering-in-frc.pdf,
// By theorem 6.10.1 of
// https://file.tavsys.net/control/controls-engineering-in-frc.pdf,
// the flywheel state-space model is:
//
// dx/dt = -G²Kₜ/(KᵥRJ)x + (GKₜ)/(RJ)u
// A = -G²Kₜ/(KᵥRJ)
// B = GKₜ/(RJ)
// dx/dt = -G²Kₜ/(KᵥRJ)x + (GKₜ)/(RJ)u
// A = -G²Kₜ/(KᵥRJ)
// B = GKₜ/(RJ)
//
// Solve for G.
//
// A/B = -G/Kᵥ
// G = -KᵥA/B
// A/B = -G/Kᵥ
// G = -KᵥA/B
//
// Solve for J.
//
// B = GKₜ/(RJ)
// J = GKₜ/(RB)
// B = GKₜ/(RJ)
// J = GKₜ/(RB)
m_gearing = -gearbox.KvRadPerSecPerVolt * plant.getA(0, 0) / plant.getB(0, 0);
m_jKgMetersSquared = m_gearing * gearbox.KtNMPerAmp / (gearbox.rOhms * plant.getB(0, 0));
}
Expand Down Expand Up @@ -156,44 +163,32 @@ public AngularAcceleration getAngularAcceleration() {
return m_angularAcceleration;
}

/**
* Returns the flywheel's torque in Newton-Meters.
*
* @return The flywheel's torque in Newton-Meters.
*/
public double getTorqueNewtonMeters() {
return getAngularAccelerationRadPerSecSq() * m_jKgMetersSquared;
}

/**
* Returns the flywheel's current draw.
*
* @return The flywheel's current draw.
*/
public double getCurrentDrawAmps() {
// I = V / R - omega / (Kv * R)
// Reductions are output over input, so a reduction of 2:1 means the motor is spinning
// Reductions are output over input, so a reduction of 2:1 means the motor is
// spinning
// 2x faster than the flywheel
return m_gearbox.getCurrent(m_x.get(0, 0) * m_gearing, m_u.get(0, 0))
* Math.signum(m_u.get(0, 0));
}

/**
* Gets the input voltage for the flywheel.
* Gets the voltage of the flywheel.
*
* @return The flywheel input voltage.
* @return The flywheel's voltage.
*/
public double getInputVoltage() {
return getInput(0);
}
public abstract double getVoltage();

/**
* Sets the input voltage for the flywheel.
* Gets the torque on the flywheel.
*
* @param volts The input voltage.
* @return The flywheel's torque in Newton-Meters.
*/
public void setInputVoltage(double volts) {
setInput(volts);
clampInput(RobotController.getBatteryVoltage());
}
public abstract double getTorqueNewtonMeters();

}
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.

package edu.wpi.first.wpilibj.simulation;

import edu.wpi.first.math.numbers.N1;
import edu.wpi.first.math.system.LinearSystem;
import edu.wpi.first.math.system.plant.DCMotor;
import edu.wpi.first.math.system.plant.LinearSystemId;

/** Represents a simulated flywheel mechanism. */
public class FlywheelSimTorque extends FlywheelSim {

/**
* Creates a simulated flywheel mechanism.
*
* @param plant The linear system that represents the flywheel. Use either {@link
* LinearSystemId#createFlywheelSystem(DCMotor, double, double)} if using physical constants
* or {@link LinearSystemId#identifyVelocitySystem(double, double)} if using system
* characterization.
* @param gearbox The type of and number of motors in the flywheel gearbox.
* @param measurementStdDevs The standard deviations of the measurements. Can be omitted if no
* noise is desired. If present must have 1 element for velocity.
*/
public FlywheelSimTorque(
LinearSystem<N1, N1, N1> plant, DCMotor gearbox, double... measurementStdDevs) {
super(plant, gearbox, measurementStdDevs);
}

/**
* Sets the input torque for the flywheel.
*
* @param volts The input torque.
*/
public void setInputTorque(double torqueNM) {
setInput(torqueNM);
}

@Override
public double getVoltage() {
// TODO Auto-generated method stub
throw new UnsupportedOperationException("Unimplemented method 'getVoltage'");
}

@Override
public double getTorqueNewtonMeters() {
// TODO Auto-generated method stub
throw new UnsupportedOperationException("Unimplemented method 'getTorqueNewtonMeters'");
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,69 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.

package edu.wpi.first.wpilibj.simulation;

import edu.wpi.first.math.numbers.N1;
import edu.wpi.first.math.system.LinearSystem;
import edu.wpi.first.math.system.plant.DCMotor;
import edu.wpi.first.math.system.plant.LinearSystemId;
import edu.wpi.first.wpilibj.RobotController;

/** Represents a simulated flywheel mechanism. */
public class FlywheelSimVoltage extends FlywheelSim {

/**
* Creates a simulated flywheel mechanism.
*
* @param plant The linear system that represents the flywheel. Use
* either {@link
* LinearSystemId#createFlywheelSystem(DCMotor, double, double)}
* if using physical constants
* or
* {@link LinearSystemId#identifyVelocitySystem(double, double)}
* if using system
* characterization.
* @param gearbox The type of and number of motors in the flywheel
* gearbox.
* @param measurementStdDevs The standard deviations of the measurements. Can be
* omitted if no
* noise is desired. If present must have 1 element
* for velocity.
*/
public FlywheelSimVoltage(
LinearSystem<N1, N1, N1> plant, DCMotor gearbox, double... measurementStdDevs) {
super(plant, gearbox, measurementStdDevs);

}

/**
* Sets the input voltage for the flywheel.
*
* @param volts The input voltage.
*/
public void setInputVoltage(double volts) {
setInput(volts);
clampInput(RobotController.getBatteryVoltage());
}

/**
* Gets the input voltage for the flywheel.
*
* @return The flywheel input voltage.
*/
@Override
public double getVoltage() {
return getInput(0);
}

/**
* Gets the torque on the flywheel.
*
* @return The flywheel's torque in Newton-Meters.
*/
@Override
public double getTorqueNewtonMeters() {
return getAngularAccelerationRadPerSecSq() * m_jKgMetersSquared;
}
}

0 comments on commit 1dff657

Please sign in to comment.