Class SharpIR

java.lang.Object
edu.wpi.first.wpilibj.SharpIR
All Implemented Interfaces:
Sendable, AutoCloseable

public class SharpIR extends Object implements Sendable, AutoCloseable
SharpIR analog distance sensor class. These distance measuring sensors output an analog voltage corresponding to the detection distance.

Teams are advised that the case of these sensors are conductive and grounded, so they should not be mounted on a metallic surface on an FRC robot.

  • Constructor Summary

    Constructors
    Constructor
    Description
    SharpIR(int channel, double a, double b, double min, double max)
    Manually construct a SharpIR object.
  • Method Summary

    Modifier and Type
    Method
    Description
    void
     
    int
    Get the analog input channel number.
    double
    Get the range in meters from the distance sensor.
    static SharpIR
    GP2Y0A02YK0F(int channel)
    Sharp GP2Y0A02YK0F is an analog IR sensor capable of measuring distances from 20 cm to 150 cm.
    static SharpIR
    GP2Y0A21YK0F(int channel)
    Sharp GP2Y0A21YK0F is an analog IR sensor capable of measuring distances from 10 cm to 80 cm.
    static SharpIR
    GP2Y0A41SK0F(int channel)
    Sharp GP2Y0A41SK0F is an analog IR sensor capable of measuring distances from 4 cm to 30 cm.
    static SharpIR
    GP2Y0A51SK0F(int channel)
    Sharp GP2Y0A51SK0F is an analog IR sensor capable of measuring distances from 2 cm to 15 cm.
    void
    Initializes this Sendable object.

    Methods inherited from class java.lang.Object

    clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
  • Constructor Details

    • SharpIR

      public SharpIR(int channel, double a, double b, double min, double max)
      Manually construct a SharpIR object. The distance is computed using this formula: A*v ^ B. Prefer to use one of the static factories to create this device instead.
      Parameters:
      channel - AnalogInput channel
      a - Constant A
      b - Constant B
      min - Minimum distance to report in meters
      max - Maximum distance to report in meters
  • Method Details

    • GP2Y0A02YK0F

      public static SharpIR GP2Y0A02YK0F(int channel)
      Sharp GP2Y0A02YK0F is an analog IR sensor capable of measuring distances from 20 cm to 150 cm.
      Parameters:
      channel - Analog input channel the sensor is connected to
      Returns:
      sensor object
    • GP2Y0A21YK0F

      public static SharpIR GP2Y0A21YK0F(int channel)
      Sharp GP2Y0A21YK0F is an analog IR sensor capable of measuring distances from 10 cm to 80 cm.
      Parameters:
      channel - Analog input channel the sensor is connected to
      Returns:
      sensor object
    • GP2Y0A41SK0F

      public static SharpIR GP2Y0A41SK0F(int channel)
      Sharp GP2Y0A41SK0F is an analog IR sensor capable of measuring distances from 4 cm to 30 cm.
      Parameters:
      channel - Analog input channel the sensor is connected to
      Returns:
      sensor object
    • GP2Y0A51SK0F

      public static SharpIR GP2Y0A51SK0F(int channel)
      Sharp GP2Y0A51SK0F is an analog IR sensor capable of measuring distances from 2 cm to 15 cm.
      Parameters:
      channel - Analog input channel the sensor is connected to
      Returns:
      sensor object
    • close

      public void close()
      Specified by:
      close in interface AutoCloseable
    • getChannel

      public int getChannel()
      Get the analog input channel number.
      Returns:
      analog input channel
    • getRange

      public double getRange()
      Get the range in meters from the distance sensor.
      Returns:
      range in meters of the target returned by the sensor
    • initSendable

      public void initSendable(SendableBuilder builder)
      Description copied from interface: Sendable
      Initializes this Sendable object.
      Specified by:
      initSendable in interface Sendable
      Parameters:
      builder - sendable builder