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.SimBoolean;
008import edu.wpi.first.hal.SimDouble;
009import edu.wpi.first.hal.SimEnum;
010import edu.wpi.first.hal.SimInt;
011import edu.wpi.first.hal.SimLong;
012import edu.wpi.first.hal.SimValue;
013import edu.wpi.first.hal.simulation.SimDeviceCallback;
014import edu.wpi.first.hal.simulation.SimDeviceDataJNI;
015import edu.wpi.first.hal.simulation.SimValueCallback;
016
017/** Class to control the simulation side of a SimDevice. */
018public class SimDeviceSim {
019  private final int m_handle;
020
021  /**
022   * Constructs a SimDeviceSim.
023   *
024   * @param name name of the SimDevice
025   */
026  public SimDeviceSim(String name) {
027    m_handle = SimDeviceDataJNI.getSimDeviceHandle(name);
028  }
029
030  /**
031   * Constructs a SimDeviceSim.
032   *
033   * @param name name of the SimDevice
034   * @param index device index number to append to name
035   */
036  public SimDeviceSim(String name, int index) {
037    this(name + "[" + index + "]");
038  }
039
040  /**
041   * Constructs a SimDeviceSim.
042   *
043   * @param name name of the SimDevice
044   * @param index device index number to append to name
045   * @param channel device channel number to append to name
046   */
047  public SimDeviceSim(String name, int index, int channel) {
048    this(name + "[" + index + "," + channel + "]");
049  }
050
051  /**
052   * Get the property object with the given name.
053   *
054   * @param name the property name
055   * @return the property object
056   */
057  public SimValue getValue(String name) {
058    int handle = SimDeviceDataJNI.getSimValueHandle(m_handle, name);
059    if (handle <= 0) {
060      return null;
061    }
062    return new SimValue(handle);
063  }
064
065  /**
066   * Get the property object with the given name.
067   *
068   * @param name the property name
069   * @return the property object
070   */
071  public SimInt getInt(String name) {
072    int handle = SimDeviceDataJNI.getSimValueHandle(m_handle, name);
073    if (handle <= 0) {
074      return null;
075    }
076    return new SimInt(handle);
077  }
078
079  /**
080   * Get the property object with the given name.
081   *
082   * @param name the property name
083   * @return the property object
084   */
085  public SimLong getLong(String name) {
086    int handle = SimDeviceDataJNI.getSimValueHandle(m_handle, name);
087    if (handle <= 0) {
088      return null;
089    }
090    return new SimLong(handle);
091  }
092
093  /**
094   * Get the property object with the given name.
095   *
096   * @param name the property name
097   * @return the property object
098   */
099  public SimDouble getDouble(String name) {
100    int handle = SimDeviceDataJNI.getSimValueHandle(m_handle, name);
101    if (handle <= 0) {
102      return null;
103    }
104    return new SimDouble(handle);
105  }
106
107  /**
108   * Get the property object with the given name.
109   *
110   * @param name the property name
111   * @return the property object
112   */
113  public SimEnum getEnum(String name) {
114    int handle = SimDeviceDataJNI.getSimValueHandle(m_handle, name);
115    if (handle <= 0) {
116      return null;
117    }
118    return new SimEnum(handle);
119  }
120
121  /**
122   * Get the property object with the given name.
123   *
124   * @param name the property name
125   * @return the property object
126   */
127  public SimBoolean getBoolean(String name) {
128    int handle = SimDeviceDataJNI.getSimValueHandle(m_handle, name);
129    if (handle <= 0) {
130      return null;
131    }
132    return new SimBoolean(handle);
133  }
134
135  /**
136   * Get all options for the given enum.
137   *
138   * @param val the enum
139   * @return names of the different values for that enum
140   */
141  public static String[] getEnumOptions(SimEnum val) {
142    return SimDeviceDataJNI.getSimValueEnumOptions(val.getNativeHandle());
143  }
144
145  /**
146   * Get all data of this object.
147   *
148   * @return all data and fields of this object
149   */
150  public SimDeviceDataJNI.SimValueInfo[] enumerateValues() {
151    return SimDeviceDataJNI.enumerateSimValues(m_handle);
152  }
153
154  /**
155   * Get the native handle of this object.
156   *
157   * @return the handle used to refer to this object through JNI
158   */
159  public int getNativeHandle() {
160    return m_handle;
161  }
162
163  /**
164   * Register a callback to be run every time a new value is added to this device.
165   *
166   * @param callback the callback
167   * @param initialNotify should the callback be run with the initial state
168   * @return the {@link CallbackStore} object associated with this callback. Save a reference to
169   *     this object so GC doesn't cancel the callback.
170   */
171  public CallbackStore registerValueCreatedCallback(
172      SimValueCallback callback, boolean initialNotify) {
173    int uid = SimDeviceDataJNI.registerSimValueCreatedCallback(m_handle, callback, initialNotify);
174    return new CallbackStore(uid, SimDeviceDataJNI::cancelSimValueCreatedCallback);
175  }
176
177  /**
178   * Register a callback to be run every time a value is changed on this device.
179   *
180   * @param value simulated value
181   * @param callback the callback
182   * @param initialNotify should the callback be run with the initial state
183   * @return the {@link CallbackStore} object associated with this callback. Save a reference to
184   *     this object so GC doesn't cancel the callback.
185   */
186  public CallbackStore registerValueChangedCallback(
187      SimValue value, SimValueCallback callback, boolean initialNotify) {
188    int uid =
189        SimDeviceDataJNI.registerSimValueChangedCallback(
190            value.getNativeHandle(), callback, initialNotify);
191    return new CallbackStore(uid, SimDeviceDataJNI::cancelSimValueChangedCallback);
192  }
193
194  /**
195   * Register a callback for SimDouble.reset() and similar functions. The callback is called with
196   * the old value.
197   *
198   * @param value simulated value
199   * @param callback callback
200   * @param initialNotify ignored (present for consistency)
201   * @return the {@link CallbackStore} object associated with this callback. Save a reference to
202   *     this object so GC doesn't cancel the callback.
203   */
204  public CallbackStore registerValueResetCallback(
205      SimValue value, SimValueCallback callback, boolean initialNotify) {
206    int uid =
207        SimDeviceDataJNI.registerSimValueResetCallback(
208            value.getNativeHandle(), callback, initialNotify);
209    return new CallbackStore(uid, SimDeviceDataJNI::cancelSimValueResetCallback);
210  }
211
212  /**
213   * Get all sim devices with the given prefix.
214   *
215   * @param prefix the prefix to filter sim devices
216   * @return all sim devices
217   */
218  public static SimDeviceDataJNI.SimDeviceInfo[] enumerateDevices(String prefix) {
219    return SimDeviceDataJNI.enumerateSimDevices(prefix);
220  }
221
222  /**
223   * Register a callback to be run every time a new {@link edu.wpi.first.hal.SimDevice} is created.
224   *
225   * @param prefix the prefix to filter sim devices
226   * @param callback the callback
227   * @param initialNotify should the callback be run with the initial state
228   * @return the {@link CallbackStore} object associated with this callback. Save a reference to
229   *     this object so GC doesn't cancel the callback.
230   */
231  public static CallbackStore registerDeviceCreatedCallback(
232      String prefix, SimDeviceCallback callback, boolean initialNotify) {
233    int uid = SimDeviceDataJNI.registerSimDeviceCreatedCallback(prefix, callback, initialNotify);
234    return new CallbackStore(uid, SimDeviceDataJNI::cancelSimDeviceCreatedCallback);
235  }
236
237  /**
238   * Register a callback to be run every time a {@link edu.wpi.first.hal.SimDevice} is
239   * freed/destroyed.
240   *
241   * @param prefix the prefix to filter sim devices
242   * @param callback the callback
243   * @param initialNotify should the callback be run with the initial state
244   * @return the {@link CallbackStore} object associated with this callback. Save a reference to
245   *     this object so GC doesn't cancel the callback.
246   */
247  public static CallbackStore registerDeviceFreedCallback(
248      String prefix, SimDeviceCallback callback, boolean initialNotify) {
249    int uid = SimDeviceDataJNI.registerSimDeviceFreedCallback(prefix, callback, initialNotify);
250    return new CallbackStore(uid, SimDeviceDataJNI::cancelSimDeviceFreedCallback);
251  }
252
253  /** Reset all SimDevice data. */
254  public static void resetData() {
255    SimDeviceDataJNI.resetSimDeviceData();
256  }
257}