#include <frc/SharpIR.h>
|
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.
|
|
◆ SharpIR()
frc::SharpIR::SharpIR |
( |
int | channel, |
|
|
double | a, |
|
|
double | b, |
|
|
double | minCM, |
|
|
double | maxCM ) |
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 | Analog input channel the sensor is connected to |
a | Constant A |
b | Constant B |
minCM | Minimum distance to report in centimeters |
maxCM | Maximum distance to report in centimeters |
◆ GetChannel()
int frc::SharpIR::GetChannel |
( |
| ) |
const |
Get the analog input channel number.
- Returns
- analog input channel
◆ GetRange()
units::centimeter_t frc::SharpIR::GetRange |
( |
| ) |
const |
Get the range from the distance sensor.
- Returns
- range of the target returned by the sensor
◆ GP2Y0A02YK0F()
static SharpIR frc::SharpIR::GP2Y0A02YK0F |
( |
int | channel | ) |
|
|
static |
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()
static SharpIR frc::SharpIR::GP2Y0A21YK0F |
( |
int | channel | ) |
|
|
static |
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()
static SharpIR frc::SharpIR::GP2Y0A41SK0F |
( |
int | channel | ) |
|
|
static |
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()
static SharpIR frc::SharpIR::GP2Y0A51SK0F |
( |
int | channel | ) |
|
|
static |
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
◆ InitSendable()
Initializes this Sendable object.
- Parameters
-
Implements wpi::Sendable.
The documentation for this class was generated from the following file: