Class AnalogGyroSim

java.lang.Object
edu.wpi.first.wpilibj.simulation.AnalogGyroSim

public class AnalogGyroSim extends Object
Class to control a simulated analog gyro.
  • Constructor Details

    • AnalogGyroSim

      public AnalogGyroSim(AnalogGyro gyro)
      Constructs from an AnalogGyro object.
      Parameters:
      gyro - AnalogGyro to simulate
    • AnalogGyroSim

      public AnalogGyroSim(int channel)
      Constructs from an analog input channel number.
      Parameters:
      channel - Channel number
  • Method Details

    • registerAngleCallback

      public CallbackStore registerAngleCallback(NotifyCallback callback, boolean initialNotify)
      Register a callback on the angle.
      Parameters:
      callback - the callback that will be called whenever the angle changes
      initialNotify - if true, the callback will be run on the initial value
      Returns:
      the CallbackStore object associated with this callback.
    • getAngle

      public double getAngle()
      Get the current angle of the gyro.
      Returns:
      the angle measured by the gyro
    • setAngle

      public void setAngle(double angle)
      Change the angle measured by the gyro.
      Parameters:
      angle - the new value
    • registerRateCallback

      public CallbackStore registerRateCallback(NotifyCallback callback, boolean initialNotify)
      Register a callback on the rate.
      Parameters:
      callback - the callback that will be called whenever the rate changes
      initialNotify - if true, the callback will be run on the initial value
      Returns:
      the CallbackStore object associated with this callback.
    • getRate

      public double getRate()
      Get the rate of angle change on this gyro.
      Returns:
      the rate
    • setRate

      public void setRate(double rate)
      Change the rate of the gyro.
      Parameters:
      rate - the new rate
    • registerInitializedCallback

      public CallbackStore registerInitializedCallback(NotifyCallback callback, boolean initialNotify)
      Register a callback on whether the gyro is initialized.
      Parameters:
      callback - the callback that will be called whenever the gyro is initialized
      initialNotify - if true, the callback will be run on the initial value
      Returns:
      the CallbackStore object associated with this callback.
    • getInitialized

      public boolean getInitialized()
      Check if the gyro is initialized.
      Returns:
      true if initialized
    • setInitialized

      public void setInitialized(boolean initialized)
      Set whether this gyro is initialized.
      Parameters:
      initialized - the new value
    • resetData

      public void resetData()
      Reset all simulation data for this object.