WPILibC++ 2024.1.1-beta-4
Ultrasonic.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 <atomic>
8#include <memory>
9#include <thread>
10#include <vector>
11
12#include <hal/SimDevice.h>
13#include <units/length.h>
14#include <units/time.h>
15#include <units/velocity.h>
18
19#include "frc/Counter.h"
20
21namespace frc {
22
23class DigitalInput;
24class DigitalOutput;
25
26/**
27 * Ultrasonic rangefinder class.
28 *
29 * The Ultrasonic rangefinder measures absolute distance based on the round-trip
30 * time of a ping generated by the controller. These sensors use two
31 * transducers, a speaker and a microphone both tuned to the ultrasonic range. A
32 * common ultrasonic sensor, the Daventech SRF04 requires a short pulse to be
33 * generated on a digital channel. This causes the chirp to be emitted. A second
34 * line becomes high as the ping is transmitted and goes low when the echo is
35 * received. The time that the line is high determines the round trip distance
36 * (time of flight).
37 */
39 public wpi::SendableHelper<Ultrasonic> {
40 public:
41 /**
42 * Create an instance of the Ultrasonic Sensor.
43 *
44 * This is designed to support the Daventech SRF04 and Vex ultrasonic sensors.
45 *
46 * @param pingChannel The digital output channel that sends the pulse to
47 * initiate the sensor sending the ping.
48 * @param echoChannel The digital input channel that receives the echo. The
49 * length of time that the echo is high represents the
50 * round trip time of the ping, and the distance.
51 */
52 Ultrasonic(int pingChannel, int echoChannel);
53
54 /**
55 * Create an instance of an Ultrasonic Sensor from a DigitalInput for the echo
56 * channel and a DigitalOutput for the ping channel.
57 *
58 * @param pingChannel The digital output object that starts the sensor doing a
59 * ping. Requires a 10uS pulse to start.
60 * @param echoChannel The digital input object that times the return pulse to
61 * determine the range.
62 */
63 Ultrasonic(DigitalOutput* pingChannel, DigitalInput* echoChannel);
64
65 /**
66 * Create an instance of an Ultrasonic Sensor from a DigitalInput for the echo
67 * channel and a DigitalOutput for the ping channel.
68 *
69 * @param pingChannel The digital output object that starts the sensor doing a
70 * ping. Requires a 10uS pulse to start.
71 * @param echoChannel The digital input object that times the return pulse to
72 * determine the range.
73 */
74 Ultrasonic(DigitalOutput& pingChannel, DigitalInput& echoChannel);
75
76 /**
77 * Create an instance of an Ultrasonic Sensor from a DigitalInput for the echo
78 * channel and a DigitalOutput for the ping channel.
79 *
80 * @param pingChannel The digital output object that starts the sensor doing a
81 * ping. Requires a 10uS pulse to start.
82 * @param echoChannel The digital input object that times the return pulse to
83 * determine the range.
84 */
85 Ultrasonic(std::shared_ptr<DigitalOutput> pingChannel,
86 std::shared_ptr<DigitalInput> echoChannel);
87
88 ~Ultrasonic() override;
89
90 Ultrasonic(Ultrasonic&&) = default;
92
93 int GetEchoChannel() const;
94
95 /**
96 * Single ping to ultrasonic sensor.
97 *
98 * Send out a single ping to the ultrasonic sensor. This only works if
99 * automatic (round robin) mode is disabled. A single ping is sent out, and
100 * the counter should count the semi-period when it comes in. The counter is
101 * reset to make the current value invalid.
102 */
103 void Ping();
104
105 /**
106 * Check if there is a valid range measurement.
107 *
108 * The ranges are accumulated in a counter that will increment on each edge of
109 * the echo (return) signal. If the count is not at least 2, then the range
110 * has not yet been measured, and is invalid.
111 */
112 bool IsRangeValid() const;
113
114 /**
115 * Turn Automatic mode on/off.
116 *
117 * When in Automatic mode, all sensors will fire in round robin, waiting a set
118 * time between each sensor.
119 *
120 * @param enabling Set to true if round robin scheduling should start for all
121 * the ultrasonic sensors. This scheduling method assures that
122 * the sensors are non-interfering because no two sensors fire
123 * at the same time. If another scheduling algorithm is
124 * preferred, it can be implemented by pinging the sensors
125 * manually and waiting for the results to come back.
126 */
127 static void SetAutomaticMode(bool enabling);
128
129 /**
130 * Get the range from the ultrasonic sensor.
131 *
132 * @return Range of the target returned from the ultrasonic sensor. If there
133 * is no valid value yet, i.e. at least one measurement hasn't
134 * completed, then return 0.
135 */
136 units::meter_t GetRange() const;
137
138 bool IsEnabled() const;
139
140 void SetEnabled(bool enable);
141
142 void InitSendable(wpi::SendableBuilder& builder) override;
143
144 private:
145 /**
146 * Initialize the Ultrasonic Sensor.
147 *
148 * This is the common code that initializes the ultrasonic sensor given that
149 * there are two digital I/O channels allocated. If the system was running in
150 * automatic mode (round robin) when the new sensor is added, it is stopped,
151 * the sensor is added, then automatic mode is restored.
152 */
153 void Initialize();
154
155 /**
156 * Background task that goes through the list of ultrasonic sensors and pings
157 * each one in turn. The counter is configured to read the timing of the
158 * returned echo pulse.
159 *
160 * DANGER WILL ROBINSON, DANGER WILL ROBINSON:
161 * This code runs as a task and assumes that none of the ultrasonic sensors
162 * will change while it's running. Make sure to disable automatic mode before
163 * touching the list.
164 */
165 static void UltrasonicChecker();
166
167 // Time (usec) for the ping trigger pulse.
168 static constexpr auto kPingTime = 10_us;
169
170 // Max time (ms) between readings.
171 static constexpr auto kMaxUltrasonicTime = 0.1_s;
172 static constexpr auto kSpeedOfSound = 1130_fps;
173
174 // Thread doing the round-robin automatic sensing
175 static std::thread m_thread;
176
177 // Ultrasonic sensors
178 static std::vector<Ultrasonic*> m_sensors;
179
180 // Automatic round-robin mode
181 static std::atomic<bool> m_automaticEnabled;
182
183 std::shared_ptr<DigitalOutput> m_pingChannel;
184 std::shared_ptr<DigitalInput> m_echoChannel;
185 bool m_enabled = false;
186 Counter m_counter;
187
188 hal::SimDevice m_simDevice;
189 hal::SimBoolean m_simRangeValid;
190 hal::SimDouble m_simRange;
191};
192
193} // namespace frc
Class for counting the number of ticks on a digital input channel.
Definition: Counter.h:35
Class to read a digital input.
Definition: DigitalInput.h:27
Class to write to digital outputs.
Definition: DigitalOutput.h:25
Ultrasonic rangefinder class.
Definition: Ultrasonic.h:39
void InitSendable(wpi::SendableBuilder &builder) override
Initializes this Sendable object.
Ultrasonic(Ultrasonic &&)=default
static void SetAutomaticMode(bool enabling)
Turn Automatic mode on/off.
Ultrasonic(std::shared_ptr< DigitalOutput > pingChannel, std::shared_ptr< DigitalInput > echoChannel)
Create an instance of an Ultrasonic Sensor from a DigitalInput for the echo channel and a DigitalOutp...
~Ultrasonic() override
void Ping()
Single ping to ultrasonic sensor.
Ultrasonic(int pingChannel, int echoChannel)
Create an instance of the Ultrasonic Sensor.
void SetEnabled(bool enable)
int GetEchoChannel() const
Ultrasonic(DigitalOutput &pingChannel, DigitalInput &echoChannel)
Create an instance of an Ultrasonic Sensor from a DigitalInput for the echo channel and a DigitalOutp...
Ultrasonic & operator=(Ultrasonic &&)=default
bool IsEnabled() const
units::meter_t GetRange() const
Get the range from the ultrasonic sensor.
Ultrasonic(DigitalOutput *pingChannel, DigitalInput *echoChannel)
Create an instance of an Ultrasonic Sensor from a DigitalInput for the echo channel and a DigitalOutp...
bool IsRangeValid() const
Check if there is a valid range measurement.
C++ wrapper around a HAL simulator boolean value handle.
Definition: SimDevice.h:610
A move-only C++ wrapper around a HAL simulator device handle.
Definition: SimDevice.h:644
C++ wrapper around a HAL simulator double value handle.
Definition: SimDevice.h:535
Definition: SendableBuilder.h:18
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: AprilTagPoseEstimator.h:15