WPILibC++ 2025.0.0-alpha-1-2-g5e745bc
SharpIR.h
Go to the documentation of this file.
1// Copyright (c) FIRST and other WPILib contributors.
2// Open Source Software; you can modify and/or share it under the terms of
3// the WPILib BSD license file in the root directory of this project.
4
5#pragma once
6
7#include <hal/SimDevice.h>
8#include <units/length.h>
11
12#include "frc/AnalogInput.h"
13
14namespace frc {
15
16class SharpIR : public wpi::Sendable, public wpi::SendableHelper<SharpIR> {
17 public:
18 /**
19 * Sharp GP2Y0A02YK0F is an analog IR sensor capable of measuring
20 * distances from 20cm to 150cm.
21 *
22 * @param channel Analog input channel the sensor is connected to
23 *
24 * @return sensor object
25 */
26 static SharpIR GP2Y0A02YK0F(int channel);
27
28 /**
29 * Sharp GP2Y0A21YK0F is an analog IR sensor capable of measuring
30 * distances from 10cm to 80cm.
31 *
32 * @param channel Analog input channel the sensor is connected to
33 *
34 * @return sensor object
35 */
36 static SharpIR GP2Y0A21YK0F(int channel);
37
38 /**
39 * Sharp GP2Y0A41SK0F is an analog IR sensor capable of measuring
40 * distances from 4cm to 30cm.
41 *
42 * @param channel Analog input channel the sensor is connected to
43 *
44 * @return sensor object
45 */
46 static SharpIR GP2Y0A41SK0F(int channel);
47
48 /**
49 * Sharp GP2Y0A51SK0F is an analog IR sensor capable of measuring
50 * distances from 2cm to 15cm.
51 *
52 * @param channel Analog input channel the sensor is connected to
53 *
54 * @return sensor object
55 */
56 static SharpIR GP2Y0A51SK0F(int channel);
57
58 /**
59 * Manually construct a SharpIR object. The distance is computed using this
60 * formula: A*v ^ B. Prefer to use one of the static factories to create this
61 * device instead.
62 *
63 * @param channel Analog input channel the sensor is connected to
64 * @param a Constant A
65 * @param b Constant B
66 * @param minCM Minimum distance to report in centimeters
67 * @param maxCM Maximum distance to report in centimeters
68 */
69 SharpIR(int channel, double a, double b, double minCM, double maxCM);
70
71 /**
72 * Get the analog input channel number.
73 *
74 * @return analog input channel
75 */
76 int GetChannel() const;
77
78 /**
79 * Get the range from the distance sensor.
80 *
81 * @return range of the target returned by the sensor
82 */
83 units::centimeter_t GetRange() const;
84
85 void InitSendable(wpi::SendableBuilder& builder) override;
86
87 private:
88 AnalogInput m_sensor;
89
90 hal::SimDevice m_simDevice;
91 hal::SimDouble m_simRange;
92
93 double m_A;
94 double m_B;
95 double m_minCM;
96 double m_maxCM;
97};
98
99} // namespace frc
Analog input class.
Definition: AnalogInput.h:31
Definition: SharpIR.h:16
static SharpIR GP2Y0A02YK0F(int channel)
Sharp GP2Y0A02YK0F is an analog IR sensor capable of measuring distances from 20cm to 150cm.
void InitSendable(wpi::SendableBuilder &builder) override
Initializes this Sendable object.
int GetChannel() const
Get the analog input channel number.
static SharpIR GP2Y0A51SK0F(int channel)
Sharp GP2Y0A51SK0F is an analog IR sensor capable of measuring distances from 2cm to 15cm.
SharpIR(int channel, double a, double b, double minCM, double maxCM)
Manually construct a SharpIR object.
static SharpIR GP2Y0A41SK0F(int channel)
Sharp GP2Y0A41SK0F is an analog IR sensor capable of measuring distances from 4cm to 30cm.
units::centimeter_t GetRange() const
Get the range from the distance sensor.
static SharpIR GP2Y0A21YK0F(int channel)
Sharp GP2Y0A21YK0F is an analog IR sensor capable of measuring distances from 10cm to 80cm.
A move-only C++ wrapper around a HAL simulator device handle.
Definition: SimDevice.h:645
C++ wrapper around a HAL simulator double value handle.
Definition: SimDevice.h:536
Helper class for building Sendable dashboard representations.
Definition: SendableBuilder.h:21
A helper class for use with objects that add themselves to SendableRegistry.
Definition: SendableHelper.h:19
Interface for Sendable objects.
Definition: Sendable.h:16
Definition: AprilTagDetector_cv.h:11
b
Definition: data.h:44