Package edu.wpi.first.wpilibj
Class SharpIR
java.lang.Object
edu.wpi.first.wpilibj.SharpIR
- All Implemented Interfaces:
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
ConstructorDescriptionSharpIR
(int channel, double a, double b, double minCM, double maxCM) Manually construct a SharpIR object. -
Method Summary
Modifier and TypeMethodDescriptionvoid
close()
int
Get the analog input channel number.double
Get the range in centimeters from the distance sensor.double
Get the range in inches from the distance sensor.static SharpIR
GP2Y0A02YK0F
(int channel) Sharp GP2Y0A02YK0F is an analog IR sensor capable of measuring distances from 20cm to 150cm.static SharpIR
GP2Y0A21YK0F
(int channel) Sharp GP2Y0A21YK0F is an analog IR sensor capable of measuring distances from 10cm to 80cm.static SharpIR
GP2Y0A41SK0F
(int channel) Sharp GP2Y0A41SK0F is an analog IR sensor capable of measuring distances from 4cm to 30cm.static SharpIR
GP2Y0A51SK0F
(int channel) Sharp GP2Y0A51SK0F is an analog IR sensor capable of measuring distances from 2cm to 15cm.void
initSendable
(SendableBuilder builder) Initializes thisSendable
object.
-
Constructor Details
-
SharpIR
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 channela
- Constant Ab
- Constant BminCM
- Minimum distance to report in centimetersmaxCM
- Maximum distance to report in centimeters
-
-
Method Details
-
GP2Y0A02YK0F
Sharp GP2Y0A02YK0F is an analog IR sensor capable of measuring distances from 20cm to 150cm.- Parameters:
channel
- Analog input channel the sensor is connected to- Returns:
- sensor object
-
GP2Y0A21YK0F
Sharp GP2Y0A21YK0F is an analog IR sensor capable of measuring distances from 10cm to 80cm.- Parameters:
channel
- Analog input channel the sensor is connected to- Returns:
- sensor object
-
GP2Y0A41SK0F
Sharp GP2Y0A41SK0F is an analog IR sensor capable of measuring distances from 4cm to 30cm.- Parameters:
channel
- Analog input channel the sensor is connected to- Returns:
- sensor object
-
GP2Y0A51SK0F
Sharp GP2Y0A51SK0F is an analog IR sensor capable of measuring distances from 2cm to 15cm.- Parameters:
channel
- Analog input channel the sensor is connected to- Returns:
- sensor object
-
close
- Specified by:
close
in interfaceAutoCloseable
-
getChannel
Get the analog input channel number.- Returns:
- analog input channel
-
getRangeInches
Get the range in inches from the distance sensor.- Returns:
- range in inches of the target returned by the sensor
-
getRangeCM
Get the range in centimeters from the distance sensor.- Returns:
- range in centimeters of the target returned by the sensor
-
initSendable
Description copied from interface:Sendable
Initializes thisSendable
object.- Specified by:
initSendable
in interfaceSendable
- Parameters:
builder
- sendable builder
-