blob: 4b3549ea254bd3f745f13e0f7ecb3c977e41fa67 [file] [log] [blame]
Brian Silvermanf7f267a2017-02-04 16:16:08 -08001/*----------------------------------------------------------------------------*/
2/* Copyright (c) FIRST 2008-2017. All Rights Reserved. */
3/* Open Source Software - may be modified and shared by FRC teams. The code */
4/* must be accompanied by the FIRST BSD license file in the root directory of */
5/* the project. */
6/*----------------------------------------------------------------------------*/
7
8#include "Ultrasonic.h"
9
10#include "Counter.h"
11#include "DigitalInput.h"
12#include "DigitalOutput.h"
13#include "HAL/HAL.h"
14#include "LiveWindow/LiveWindow.h"
15#include "Timer.h"
16#include "Utility.h"
17#include "WPIErrors.h"
18
19using namespace frc;
20
21// Time (sec) for the ping trigger pulse.
22constexpr double Ultrasonic::kPingTime;
23// Priority that the ultrasonic round robin task runs.
24const int Ultrasonic::kPriority;
25// Max time (ms) between readings.
26constexpr double Ultrasonic::kMaxUltrasonicTime;
27constexpr double Ultrasonic::kSpeedOfSoundInchesPerSec;
28// automatic round robin mode
29std::atomic<bool> Ultrasonic::m_automaticEnabled{false};
30std::set<Ultrasonic*> Ultrasonic::m_sensors;
31std::thread Ultrasonic::m_thread;
32
33/**
34 * Background task that goes through the list of ultrasonic sensors and pings
35 * each one in turn. The counter is configured to read the timing of the
36 * returned echo pulse.
37 *
38 * DANGER WILL ROBINSON, DANGER WILL ROBINSON:
39 * This code runs as a task and assumes that none of the ultrasonic sensors
40 * will change while it's running. Make sure to disable automatic mode before
41 * touching the list.
42 */
43void Ultrasonic::UltrasonicChecker() {
44 while (m_automaticEnabled) {
45 for (auto& sensor : m_sensors) {
46 if (!m_automaticEnabled) break;
47
48 if (sensor->IsEnabled()) {
49 sensor->m_pingChannel->Pulse(kPingTime); // do the ping
50 }
51
52 Wait(0.1); // wait for ping to return
53 }
54 }
55}
56
57/**
58 * Initialize the Ultrasonic Sensor.
59 *
60 * This is the common code that initializes the ultrasonic sensor given that
61 * there are two digital I/O channels allocated. If the system was running in
62 * automatic mode (round robin) when the new sensor is added, it is stopped,
63 * the sensor is added, then automatic mode is restored.
64 */
65void Ultrasonic::Initialize() {
66 bool originalMode = m_automaticEnabled;
67 SetAutomaticMode(false); // kill task when adding a new sensor
68 // link this instance on the list
69 m_sensors.insert(this);
70
71 m_counter.SetMaxPeriod(1.0);
72 m_counter.SetSemiPeriodMode(true);
73 m_counter.Reset();
74 m_enabled = true; // make it available for round robin scheduling
75 SetAutomaticMode(originalMode);
76
77 static int instances = 0;
78 instances++;
79 HAL_Report(HALUsageReporting::kResourceType_Ultrasonic, instances);
80 LiveWindow::GetInstance()->AddSensor("Ultrasonic",
81 m_echoChannel->GetChannel(), this);
82}
83
84/**
85 * Create an instance of the Ultrasonic Sensor.
86 *
87 * This is designed to support the Daventech SRF04 and Vex ultrasonic
88 * sensors.
89 *
90 * @param pingChannel The digital output channel that sends the pulse to
91 * initiate the sensor sending the ping.
92 * @param echoChannel The digital input channel that receives the echo. The
93 * length of time that the echo is high represents the
94 * round trip time of the ping, and the distance.
95 * @param units The units returned in either kInches or kMilliMeters
96 */
97Ultrasonic::Ultrasonic(int pingChannel, int echoChannel, DistanceUnit units)
98 : m_pingChannel(std::make_shared<DigitalOutput>(pingChannel)),
99 m_echoChannel(std::make_shared<DigitalInput>(echoChannel)),
100 m_counter(m_echoChannel) {
101 m_units = units;
102 Initialize();
103}
104
105/**
106 * Create an instance of an Ultrasonic Sensor from a DigitalInput for the echo
107 * channel and a DigitalOutput for the ping channel.
108 *
109 * @param pingChannel The digital output object that starts the sensor doing a
110 * ping. Requires a 10uS pulse to start.
111 * @param echoChannel The digital input object that times the return pulse to
112 * determine the range.
113 * @param units The units returned in either kInches or kMilliMeters
114 */
115Ultrasonic::Ultrasonic(DigitalOutput* pingChannel, DigitalInput* echoChannel,
116 DistanceUnit units)
117 : m_pingChannel(pingChannel, NullDeleter<DigitalOutput>()),
118 m_echoChannel(echoChannel, NullDeleter<DigitalInput>()),
119 m_counter(m_echoChannel) {
120 if (pingChannel == nullptr || echoChannel == nullptr) {
121 wpi_setWPIError(NullParameter);
122 m_units = units;
123 return;
124 }
125 m_units = units;
126 Initialize();
127}
128
129/**
130 * Create an instance of an Ultrasonic Sensor from a DigitalInput for the echo
131 * channel and a DigitalOutput for the ping channel.
132 *
133 * @param pingChannel The digital output object that starts the sensor doing a
134 * ping. Requires a 10uS pulse to start.
135 * @param echoChannel The digital input object that times the return pulse to
136 * determine the range.
137 * @param units The units returned in either kInches or kMilliMeters
138 */
139Ultrasonic::Ultrasonic(DigitalOutput& pingChannel, DigitalInput& echoChannel,
140 DistanceUnit units)
141 : m_pingChannel(&pingChannel, NullDeleter<DigitalOutput>()),
142 m_echoChannel(&echoChannel, NullDeleter<DigitalInput>()),
143 m_counter(m_echoChannel) {
144 m_units = units;
145 Initialize();
146}
147
148/**
149 * Create an instance of an Ultrasonic Sensor from a DigitalInput for the echo
150 * channel and a DigitalOutput for the ping channel.
151 *
152 * @param pingChannel The digital output object that starts the sensor doing a
153 * ping. Requires a 10uS pulse to start.
154 * @param echoChannel The digital input object that times the return pulse to
155 * determine the range.
156 * @param units The units returned in either kInches or kMilliMeters
157 */
158Ultrasonic::Ultrasonic(std::shared_ptr<DigitalOutput> pingChannel,
159 std::shared_ptr<DigitalInput> echoChannel,
160 DistanceUnit units)
161 : m_pingChannel(pingChannel),
162 m_echoChannel(echoChannel),
163 m_counter(m_echoChannel) {
164 m_units = units;
165 Initialize();
166}
167
168/**
169 * Destructor for the ultrasonic sensor.
170 *
171 * Delete the instance of the ultrasonic sensor by freeing the allocated digital
172 * channels. If the system was in automatic mode (round robin), then it is
173 * stopped, then started again after this sensor is removed (provided this
174 * wasn't the last sensor).
175 */
176Ultrasonic::~Ultrasonic() {
177 bool wasAutomaticMode = m_automaticEnabled;
178 SetAutomaticMode(false);
179
180 // No synchronization needed because the background task is stopped.
181 m_sensors.erase(this);
182
183 if (!m_sensors.empty() && wasAutomaticMode) {
184 SetAutomaticMode(true);
185 }
186}
187
188/**
189 * Turn Automatic mode on/off.
190 *
191 * When in Automatic mode, all sensors will fire in round robin, waiting a set
192 * time between each sensor.
193 *
194 * @param enabling Set to true if round robin scheduling should start for all
195 * the ultrasonic sensors. This scheduling method assures that
196 * the sensors are non-interfering because no two sensors fire
197 * at the same time. If another scheduling algorithm is
198 * prefered, it can be implemented by pinging the sensors
199 * manually and waiting for the results to come back.
200 */
201void Ultrasonic::SetAutomaticMode(bool enabling) {
202 if (enabling == m_automaticEnabled) return; // ignore the case of no change
203
204 m_automaticEnabled = enabling;
205
206 if (enabling) {
207 /* Clear all the counters so no data is valid. No synchronization is needed
208 * because the background task is stopped.
209 */
210 for (auto& sensor : m_sensors) {
211 sensor->m_counter.Reset();
212 }
213
214 m_thread = std::thread(&Ultrasonic::UltrasonicChecker);
215
216 // TODO: Currently, lvuser does not have permissions to set task priorities.
217 // Until that is the case, uncommenting this will break user code that calls
218 // Ultrasonic::SetAutomicMode().
219 // m_task.SetPriority(kPriority);
220 } else {
221 // Wait for background task to stop running
222 m_thread.join();
223
224 /* Clear all the counters (data now invalid) since automatic mode is
225 * disabled. No synchronization is needed because the background task is
226 * stopped.
227 */
228 for (auto& sensor : m_sensors) {
229 sensor->m_counter.Reset();
230 }
231 }
232}
233
234/**
235 * Single ping to ultrasonic sensor.
236 *
237 * Send out a single ping to the ultrasonic sensor. This only works if automatic
238 * (round robin) mode is disabled. A single ping is sent out, and the counter
239 * should count the semi-period when it comes in. The counter is reset to make
240 * the current value invalid.
241 */
242void Ultrasonic::Ping() {
243 wpi_assert(!m_automaticEnabled);
244 m_counter.Reset(); // reset the counter to zero (invalid data now)
245 m_pingChannel->Pulse(
246 kPingTime); // do the ping to start getting a single range
247}
248
249/**
250 * Check if there is a valid range measurement.
251 *
252 * The ranges are accumulated in a counter that will increment on each edge of
253 * the echo (return) signal. If the count is not at least 2, then the range has
254 * not yet been measured, and is invalid.
255 */
256bool Ultrasonic::IsRangeValid() const { return m_counter.Get() > 1; }
257
258/**
259 * Get the range in inches from the ultrasonic sensor.
260 *
261 * @return double Range in inches of the target returned from the ultrasonic
262 * sensor. If there is no valid value yet, i.e. at least one
263 * measurement hasn't completed, then return 0.
264 */
265double Ultrasonic::GetRangeInches() const {
266 if (IsRangeValid())
267 return m_counter.GetPeriod() * kSpeedOfSoundInchesPerSec / 2.0;
268 else
269 return 0;
270}
271
272/**
273 * Get the range in millimeters from the ultrasonic sensor.
274 *
275 * @return double Range in millimeters of the target returned by the ultrasonic
276 * sensor. If there is no valid value yet, i.e. at least one
277 * measurement hasn't completed, then return 0.
278 */
279double Ultrasonic::GetRangeMM() const { return GetRangeInches() * 25.4; }
280
281/**
282 * Get the range in the current DistanceUnit for the PIDSource base object.
283 *
284 * @return The range in DistanceUnit
285 */
286double Ultrasonic::PIDGet() {
287 switch (m_units) {
288 case Ultrasonic::kInches:
289 return GetRangeInches();
290 case Ultrasonic::kMilliMeters:
291 return GetRangeMM();
292 default:
293 return 0.0;
294 }
295}
296
297void Ultrasonic::SetPIDSourceType(PIDSourceType pidSource) {
298 if (wpi_assert(pidSource == PIDSourceType::kDisplacement)) {
299 m_pidSource = pidSource;
300 }
301}
302
303/**
304 * Set the current DistanceUnit that should be used for the PIDSource base
305 * object.
306 *
307 * @param units The DistanceUnit that should be used.
308 */
309void Ultrasonic::SetDistanceUnits(DistanceUnit units) { m_units = units; }
310
311/**
312 * Get the current DistanceUnit that is used for the PIDSource base object.
313 *
314 * @return The type of DistanceUnit that is being used.
315 */
316Ultrasonic::DistanceUnit Ultrasonic::GetDistanceUnits() const {
317 return m_units;
318}
319
320void Ultrasonic::UpdateTable() {
321 if (m_table != nullptr) {
322 m_table->PutNumber("Value", GetRangeInches());
323 }
324}
325
326void Ultrasonic::StartLiveWindowMode() {}
327
328void Ultrasonic::StopLiveWindowMode() {}
329
330std::string Ultrasonic::GetSmartDashboardType() const { return "Ultrasonic"; }
331
332void Ultrasonic::InitTable(std::shared_ptr<ITable> subTable) {
333 m_table = subTable;
334 UpdateTable();
335}
336
337std::shared_ptr<ITable> Ultrasonic::GetTable() const { return m_table; }