001// Copyright (c) FIRST and other WPILib contributors. 002// Open Source Software; you can modify and/or share it under the terms of 003// the WPILib BSD license file in the root directory of this project. 004 005package edu.wpi.first.wpilibj.simulation; 006 007import edu.wpi.first.hal.simulation.AnalogGyroDataJNI; 008import edu.wpi.first.hal.simulation.NotifyCallback; 009import edu.wpi.first.wpilibj.AnalogGyro; 010 011/** Class to control a simulated analog gyro. */ 012public class AnalogGyroSim { 013 private final int m_index; 014 015 /** 016 * Constructs from an AnalogGyro object. 017 * 018 * @param gyro AnalogGyro to simulate 019 */ 020 public AnalogGyroSim(AnalogGyro gyro) { 021 m_index = gyro.getAnalogInput().getChannel(); 022 } 023 024 /** 025 * Constructs from an analog input channel number. 026 * 027 * @param channel Channel number 028 */ 029 public AnalogGyroSim(int channel) { 030 m_index = channel; 031 } 032 033 /** 034 * Register a callback on the angle. 035 * 036 * @param callback the callback that will be called whenever the angle changes 037 * @param initialNotify if true, the callback will be run on the initial value 038 * @return the {@link CallbackStore} object associated with this callback. 039 */ 040 public CallbackStore registerAngleCallback(NotifyCallback callback, boolean initialNotify) { 041 int uid = AnalogGyroDataJNI.registerAngleCallback(m_index, callback, initialNotify); 042 return new CallbackStore(m_index, uid, AnalogGyroDataJNI::cancelAngleCallback); 043 } 044 045 /** 046 * Get the current angle of the gyro. 047 * 048 * @return the angle measured by the gyro 049 */ 050 public double getAngle() { 051 return AnalogGyroDataJNI.getAngle(m_index); 052 } 053 054 /** 055 * Change the angle measured by the gyro. 056 * 057 * @param angle the new value 058 */ 059 public void setAngle(double angle) { 060 AnalogGyroDataJNI.setAngle(m_index, angle); 061 } 062 063 /** 064 * Register a callback on the rate. 065 * 066 * @param callback the callback that will be called whenever the rate changes 067 * @param initialNotify if true, the callback will be run on the initial value 068 * @return the {@link CallbackStore} object associated with this callback. 069 */ 070 public CallbackStore registerRateCallback(NotifyCallback callback, boolean initialNotify) { 071 int uid = AnalogGyroDataJNI.registerRateCallback(m_index, callback, initialNotify); 072 return new CallbackStore(m_index, uid, AnalogGyroDataJNI::cancelRateCallback); 073 } 074 075 /** 076 * Get the rate of angle change on this gyro. 077 * 078 * @return the rate 079 */ 080 public double getRate() { 081 return AnalogGyroDataJNI.getRate(m_index); 082 } 083 084 /** 085 * Change the rate of the gyro. 086 * 087 * @param rate the new rate 088 */ 089 public void setRate(double rate) { 090 AnalogGyroDataJNI.setRate(m_index, rate); 091 } 092 093 /** 094 * Register a callback on whether the gyro is initialized. 095 * 096 * @param callback the callback that will be called whenever the gyro is initialized 097 * @param initialNotify if true, the callback will be run on the initial value 098 * @return the {@link CallbackStore} object associated with this callback. 099 */ 100 public CallbackStore registerInitializedCallback(NotifyCallback callback, boolean initialNotify) { 101 int uid = AnalogGyroDataJNI.registerInitializedCallback(m_index, callback, initialNotify); 102 return new CallbackStore(m_index, uid, AnalogGyroDataJNI::cancelInitializedCallback); 103 } 104 105 /** 106 * Check if the gyro is initialized. 107 * 108 * @return true if initialized 109 */ 110 public boolean getInitialized() { 111 return AnalogGyroDataJNI.getInitialized(m_index); 112 } 113 114 /** 115 * Set whether this gyro is initialized. 116 * 117 * @param initialized the new value 118 */ 119 public void setInitialized(boolean initialized) { 120 AnalogGyroDataJNI.setInitialized(m_index, initialized); 121 } 122 123 /** Reset all simulation data for this object. */ 124 public void resetData() { 125 AnalogGyroDataJNI.resetData(m_index); 126 } 127}