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; 006 007import edu.wpi.first.hal.HAL; 008import edu.wpi.first.hal.SimDevice; 009import edu.wpi.first.hal.SimDevice.Direction; 010import edu.wpi.first.hal.SimDouble; 011import edu.wpi.first.util.sendable.Sendable; 012import edu.wpi.first.util.sendable.SendableBuilder; 013import edu.wpi.first.util.sendable.SendableRegistry; 014 015/** 016 * SharpIR analog distance sensor class. These distance measuring sensors output an analog voltage 017 * corresponding to the detection distance. 018 * 019 * <p>Teams are advised that the case of these sensors are conductive and grounded, so they should 020 * not be mounted on a metallic surface on an FRC robot. 021 */ 022@SuppressWarnings("MethodName") 023public class SharpIR implements Sendable, AutoCloseable { 024 private AnalogInput m_sensor; 025 026 private SimDevice m_simDevice; 027 private SimDouble m_simRange; 028 029 private final double m_A; 030 private final double m_B; 031 private final double m_min; // m 032 private final double m_max; // m 033 034 /** 035 * Sharp GP2Y0A02YK0F is an analog IR sensor capable of measuring distances from 20 cm to 150 cm. 036 * 037 * @param channel Analog input channel the sensor is connected to 038 * @return sensor object 039 */ 040 public static SharpIR GP2Y0A02YK0F(int channel) { 041 return new SharpIR(channel, 62.28, -1.092, 0.2, 1.5); 042 } 043 044 /** 045 * Sharp GP2Y0A21YK0F is an analog IR sensor capable of measuring distances from 10 cm to 80 cm. 046 * 047 * @param channel Analog input channel the sensor is connected to 048 * @return sensor object 049 */ 050 public static SharpIR GP2Y0A21YK0F(int channel) { 051 return new SharpIR(channel, 26.449, -1.226, 0.1, 0.8); 052 } 053 054 /** 055 * Sharp GP2Y0A41SK0F is an analog IR sensor capable of measuring distances from 4 cm to 30 cm. 056 * 057 * @param channel Analog input channel the sensor is connected to 058 * @return sensor object 059 */ 060 public static SharpIR GP2Y0A41SK0F(int channel) { 061 return new SharpIR(channel, 12.354, -1.07, 0.04, 0.3); 062 } 063 064 /** 065 * Sharp GP2Y0A51SK0F is an analog IR sensor capable of measuring distances from 2 cm to 15 cm. 066 * 067 * @param channel Analog input channel the sensor is connected to 068 * @return sensor object 069 */ 070 public static SharpIR GP2Y0A51SK0F(int channel) { 071 return new SharpIR(channel, 5.2819, -1.161, 0.02, 0.15); 072 } 073 074 /** 075 * Manually construct a SharpIR object. The distance is computed using this formula: A*v ^ B. 076 * Prefer to use one of the static factories to create this device instead. 077 * 078 * @param channel AnalogInput channel 079 * @param a Constant A 080 * @param b Constant B 081 * @param min Minimum distance to report in meters 082 * @param max Maximum distance to report in meters 083 */ 084 @SuppressWarnings("this-escape") 085 public SharpIR(int channel, double a, double b, double min, double max) { 086 m_sensor = new AnalogInput(channel); 087 088 m_A = a; 089 m_B = b; 090 m_min = min; 091 m_max = max; 092 093 HAL.reportUsage("IO", channel, "SharpIR"); 094 SendableRegistry.add(this, "SharpIR", channel); 095 096 m_simDevice = SimDevice.create("SharpIR", m_sensor.getChannel()); 097 if (m_simDevice != null) { 098 m_simRange = m_simDevice.createDouble("Range (m)", Direction.kInput, 0.0); 099 m_sensor.setSimDevice(m_simDevice); 100 } 101 } 102 103 @Override 104 public void close() { 105 SendableRegistry.remove(this); 106 m_sensor.close(); 107 m_sensor = null; 108 109 if (m_simDevice != null) { 110 m_simDevice.close(); 111 m_simDevice = null; 112 m_simRange = null; 113 } 114 } 115 116 /** 117 * Get the analog input channel number. 118 * 119 * @return analog input channel 120 */ 121 public int getChannel() { 122 return m_sensor.getChannel(); 123 } 124 125 /** 126 * Get the range in meters from the distance sensor. 127 * 128 * @return range in meters of the target returned by the sensor 129 */ 130 public double getRange() { 131 if (m_simRange != null) { 132 return Math.clamp(m_simRange.get(), m_min, m_max); 133 } else { 134 // Don't allow zero/negative values 135 var v = Math.max(m_sensor.getVoltage(), 0.00001); 136 137 return Math.clamp(m_A * Math.pow(v, m_B) * 1e-2, m_min, m_max); 138 } 139 } 140 141 @Override 142 public void initSendable(SendableBuilder builder) { 143 builder.setSmartDashboardType("Ultrasonic"); 144 builder.addDoubleProperty("Value", this::getRange, null); 145 } 146}