Class FlywheelSim

    • Constructor Detail

      • FlywheelSim

        public FlywheelSim​(LinearSystem<N1,​N1,​N1> plant,
                           DCMotor gearbox,
                           double gearing)
        Creates a simulated flywheel mechanism.
        Parameters:
        plant - The linear system that represents the flywheel.
        gearbox - The type of and number of motors in the flywheel gearbox.
        gearing - The gearing of the flywheel (numbers greater than 1 represent reductions).
      • FlywheelSim

        public FlywheelSim​(LinearSystem<N1,​N1,​N1> plant,
                           DCMotor gearbox,
                           double gearing,
                           Matrix<N1,​N1> measurementStdDevs)
        Creates a simulated flywheel mechanism.
        Parameters:
        plant - The linear system that represents the flywheel.
        gearbox - The type of and number of motors in the flywheel gearbox.
        gearing - The gearing of the flywheel (numbers greater than 1 represent reductions).
        measurementStdDevs - The standard deviations of the measurements.
      • FlywheelSim

        public FlywheelSim​(DCMotor gearbox,
                           double gearing,
                           double jKgMetersSquared)
        Creates a simulated flywheel mechanism.
        Parameters:
        gearbox - The type of and number of motors in the flywheel gearbox.
        gearing - The gearing of the flywheel (numbers greater than 1 represent reductions).
        jKgMetersSquared - The moment of inertia of the flywheel. If this is unknown, use the FlywheelSim(LinearSystem, DCMotor, double, Matrix) constructor.
      • FlywheelSim

        public FlywheelSim​(DCMotor gearbox,
                           double gearing,
                           double jKgMetersSquared,
                           Matrix<N1,​N1> measurementStdDevs)
        Creates a simulated flywheel mechanism.
        Parameters:
        gearbox - The type of and number of motors in the flywheel gearbox.
        gearing - The gearing of the flywheel (numbers greater than 1 represent reductions).
        jKgMetersSquared - The moment of inertia of the flywheel. If this is unknown, use the FlywheelSim(LinearSystem, DCMotor, double, Matrix) constructor.
        measurementStdDevs - The standard deviations of the measurements.
    • Method Detail

      • getAngularVelocityRadPerSec

        public double getAngularVelocityRadPerSec()
        Returns the flywheel velocity.
        Returns:
        The flywheel velocity.
      • getAngularVelocityRPM

        public double getAngularVelocityRPM()
        Returns the flywheel velocity in RPM.
        Returns:
        The flywheel velocity in RPM.
      • setInputVoltage

        public void setInputVoltage​(double volts)
        Sets the input voltage for the flywheel.
        Parameters:
        volts - The input voltage.