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.math.util.Units;
010import edu.wpi.first.wpilibj.Ultrasonic;
011
012public class UltrasonicSim {
013  private final SimBoolean m_simRangeValid;
014  private final SimDouble m_simRange;
015
016  /**
017   * Constructor.
018   *
019   * @param ultrasonic The real ultrasonic to simulate
020   */
021  public UltrasonicSim(Ultrasonic ultrasonic) {
022    SimDeviceSim simDevice = new SimDeviceSim("Ultrasonic", ultrasonic.getEchoChannel());
023    m_simRangeValid = simDevice.getBoolean("Range Valid");
024    m_simRange = simDevice.getDouble("Range (in)");
025  }
026
027  public void setRangeValid(boolean valid) {
028    m_simRangeValid.set(valid);
029  }
030
031  public void setRangeInches(double inches) {
032    m_simRange.set(inches);
033  }
034
035  public void setRangeMeters(double meters) {
036    m_simRange.set(Units.metersToInches(meters));
037  }
038}