Package edu.wpi.first.wpilibj.simulation
Class AnalogGyroSim
java.lang.Object
edu.wpi.first.wpilibj.simulation.AnalogGyroSim
Class to control a simulated analog gyro.
-
Constructor Summary
ConstructorDescriptionAnalogGyroSim
(int channel) Constructs from an analog input channel number.AnalogGyroSim
(AnalogGyro gyro) Constructs from an AnalogGyro object. -
Method Summary
Modifier and TypeMethodDescriptiondouble
getAngle()
Get the current angle of the gyro.boolean
Check if the gyro is initialized.double
getRate()
Get the rate of angle change on this gyro.registerAngleCallback
(NotifyCallback callback, boolean initialNotify) Register a callback on the angle.registerInitializedCallback
(NotifyCallback callback, boolean initialNotify) Register a callback on whether the gyro is initialized.registerRateCallback
(NotifyCallback callback, boolean initialNotify) Register a callback on the rate.void
Reset all simulation data for this object.void
setAngle
(double angle) Change the angle measured by the gyro.void
setInitialized
(boolean initialized) Set whether this gyro is initialized.void
setRate
(double rate) Change the rate of the gyro.
-
Constructor Details
-
AnalogGyroSim
Constructs from an AnalogGyro object.- Parameters:
gyro
- AnalogGyro to simulate
-
AnalogGyroSim
Constructs from an analog input channel number.- Parameters:
channel
- Channel number
-
-
Method Details
-
registerAngleCallback
Register a callback on the angle.- Parameters:
callback
- the callback that will be called whenever the angle changesinitialNotify
- if true, the callback will be run on the initial value- Returns:
- the
CallbackStore
object associated with this callback.
-
getAngle
Get the current angle of the gyro.- Returns:
- the angle measured by the gyro
-
setAngle
Change the angle measured by the gyro.- Parameters:
angle
- the new value
-
registerRateCallback
Register a callback on the rate.- Parameters:
callback
- the callback that will be called whenever the rate changesinitialNotify
- if true, the callback will be run on the initial value- Returns:
- the
CallbackStore
object associated with this callback.
-
getRate
Get the rate of angle change on this gyro.- Returns:
- the rate
-
setRate
Change the rate of the gyro.- Parameters:
rate
- the new rate
-
registerInitializedCallback
Register a callback on whether the gyro is initialized.- Parameters:
callback
- the callback that will be called whenever the gyro is initializedinitialNotify
- if true, the callback will be run on the initial value- Returns:
- the
CallbackStore
object associated with this callback.
-
getInitialized
Check if the gyro is initialized.- Returns:
- true if initialized
-
setInitialized
Set whether this gyro is initialized.- Parameters:
initialized
- the new value
-
resetData
Reset all simulation data for this object.
-