WPILibC++ 2025.0.0-alpha-1-9-ga2beb75
frc::SharpIR Class Reference

#include <frc/SharpIR.h>

Inheritance diagram for frc::SharpIR:
wpi::Sendable wpi::SendableHelper< SharpIR >

Public Member Functions

 SharpIR (int channel, double a, double b, double minCM, double maxCM)
 Manually construct a SharpIR object. More...
 
int GetChannel () const
 Get the analog input channel number. More...
 
units::centimeter_t GetRange () const
 Get the range from the distance sensor. More...
 
void InitSendable (wpi::SendableBuilder &builder) override
 Initializes this Sendable object. More...
 
- Public Member Functions inherited from wpi::Sendable
virtual ~Sendable ()=default
 
virtual void InitSendable (SendableBuilder &builder)=0
 Initializes this Sendable object. More...
 
- Public Member Functions inherited from wpi::SendableHelper< SharpIR >
 SendableHelper (const SendableHelper &rhs)=default
 
 SendableHelper (SendableHelper &&rhs)
 
SendableHelperoperator= (const SendableHelper &rhs)=default
 
SendableHelperoperator= (SendableHelper &&rhs)
 

Static Public Member Functions

static SharpIR GP2Y0A02YK0F (int channel)
 Sharp GP2Y0A02YK0F is an analog IR sensor capable of measuring distances from 20cm to 150cm. More...
 
static SharpIR GP2Y0A21YK0F (int channel)
 Sharp GP2Y0A21YK0F is an analog IR sensor capable of measuring distances from 10cm to 80cm. More...
 
static SharpIR GP2Y0A41SK0F (int channel)
 Sharp GP2Y0A41SK0F is an analog IR sensor capable of measuring distances from 4cm to 30cm. More...
 
static SharpIR GP2Y0A51SK0F (int channel)
 Sharp GP2Y0A51SK0F is an analog IR sensor capable of measuring distances from 2cm to 15cm. More...
 

Additional Inherited Members

- Protected Member Functions inherited from wpi::SendableHelper< SharpIR >
 SendableHelper ()=default
 
 ~SendableHelper ()
 

Constructor & Destructor Documentation

◆ 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
channelAnalog input channel the sensor is connected to
aConstant A
bConstant B
minCMMinimum distance to report in centimeters
maxCMMaximum distance to report in centimeters

Member Function Documentation

◆ 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
channelAnalog 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
channelAnalog 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
channelAnalog 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
channelAnalog input channel the sensor is connected to
Returns
sensor object

◆ InitSendable()

void frc::SharpIR::InitSendable ( wpi::SendableBuilder builder)
overridevirtual

Initializes this Sendable object.

Parameters
buildersendable builder

Implements wpi::Sendable.


The documentation for this class was generated from the following file: