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.SimDouble; 008import edu.wpi.first.math.util.Units; 009import edu.wpi.first.wpilibj.SharpIR; 010 011/** Simulation class for Sharp IR sensors. */ 012public class SharpIRSim { 013 private final SimDouble m_simRange; 014 015 /** 016 * Constructor. 017 * 018 * @param sharpIR The real sensor to simulate 019 */ 020 public SharpIRSim(SharpIR sharpIR) { 021 this(sharpIR.getChannel()); 022 } 023 024 /** 025 * Constructor. 026 * 027 * @param channel Analog channel for this sensor 028 */ 029 public SharpIRSim(int channel) { 030 SimDeviceSim simDevice = new SimDeviceSim("SharpIR", channel); 031 m_simRange = simDevice.getDouble("Range (cm)"); 032 } 033 034 /** 035 * Set the range in inches returned by the distance sensor. 036 * 037 * @param inches range in inches of the target returned by the sensor 038 */ 039 public void setRangeInches(double inches) { 040 m_simRange.set(Units.inchesToMeters(inches) * 100.0); 041 } 042 043 /** 044 * Set the range in centimeters returned by the distance sensor. 045 * 046 * @param cm range in centimeters of the target returned by the sensor 047 */ 048 public void setRangeCm(double cm) { 049 m_simRange.set(cm); 050 } 051}