blob: 12d688d17f7d6add080cb6207131c5041aa44920 [file] [log] [blame]
Brian Silverman8fce7482020-01-05 13:18:21 -08001/*----------------------------------------------------------------------------*/
2/* Copyright (c) 2016-2019 FIRST. 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 "hal/AnalogGyro.h"
9
10#include <thread>
11
12#include <wpi/raw_ostream.h>
13
14#include "AnalogInternal.h"
15#include "HALInitializer.h"
16#include "hal/AnalogAccumulator.h"
17#include "hal/AnalogInput.h"
18#include "hal/handles/IndexedHandleResource.h"
19
20namespace {
21
22struct AnalogGyro {
23 HAL_AnalogInputHandle handle;
24 double voltsPerDegreePerSecond;
25 double offset;
26 int32_t center;
27};
28
29} // namespace
30
31static constexpr uint32_t kOversampleBits = 10;
32static constexpr uint32_t kAverageBits = 0;
33static constexpr double kSamplesPerSecond = 50.0;
34static constexpr double kCalibrationSampleTime = 5.0;
35static constexpr double kDefaultVoltsPerDegreePerSecond = 0.007;
36
37using namespace hal;
38
39static IndexedHandleResource<HAL_GyroHandle, AnalogGyro, kNumAccumulators,
40 HAL_HandleEnum::AnalogGyro>* analogGyroHandles;
41
42namespace hal {
43namespace init {
44void InitializeAnalogGyro() {
45 static IndexedHandleResource<HAL_GyroHandle, AnalogGyro, kNumAccumulators,
46 HAL_HandleEnum::AnalogGyro>
47 agHandles;
48 analogGyroHandles = &agHandles;
49}
50} // namespace init
51} // namespace hal
52
53static void Wait(double seconds) {
54 if (seconds < 0.0) return;
55 std::this_thread::sleep_for(std::chrono::duration<double>(seconds));
56}
57
58extern "C" {
59
60HAL_GyroHandle HAL_InitializeAnalogGyro(HAL_AnalogInputHandle analogHandle,
61 int32_t* status) {
62 hal::init::CheckInit();
63 if (!HAL_IsAccumulatorChannel(analogHandle, status)) {
64 if (*status == 0) {
65 *status = HAL_INVALID_ACCUMULATOR_CHANNEL;
66 }
67 return HAL_kInvalidHandle;
68 }
69
70 // handle known to be correct, so no need to type check
71 int16_t channel = getHandleIndex(analogHandle);
72
73 auto handle = analogGyroHandles->Allocate(channel, status);
74
75 if (*status != 0)
76 return HAL_kInvalidHandle; // failed to allocate. Pass error back.
77
78 // Initialize port structure
79 auto gyro = analogGyroHandles->Get(handle);
80 if (gyro == nullptr) { // would only error on thread issue
81 *status = HAL_HANDLE_ERROR;
82 return HAL_kInvalidHandle;
83 }
84
85 gyro->handle = analogHandle;
86 gyro->voltsPerDegreePerSecond = 0;
87 gyro->offset = 0;
88 gyro->center = 0;
89
90 return handle;
91}
92
93void HAL_SetupAnalogGyro(HAL_GyroHandle handle, int32_t* status) {
94 auto gyro = analogGyroHandles->Get(handle);
95 if (gyro == nullptr) {
96 *status = HAL_HANDLE_ERROR;
97 return;
98 }
99
100 gyro->voltsPerDegreePerSecond = kDefaultVoltsPerDegreePerSecond;
101
102 HAL_SetAnalogAverageBits(gyro->handle, kAverageBits, status);
103 if (*status != 0) return;
104 HAL_SetAnalogOversampleBits(gyro->handle, kOversampleBits, status);
105 if (*status != 0) return;
106 double sampleRate =
107 kSamplesPerSecond * (1 << (kAverageBits + kOversampleBits));
108 HAL_SetAnalogSampleRate(sampleRate, status);
109 if (*status != 0) return;
110 Wait(0.1);
111
112 HAL_SetAnalogGyroDeadband(handle, 0.0, status);
113 if (*status != 0) return;
114}
115
116void HAL_FreeAnalogGyro(HAL_GyroHandle handle) {
117 analogGyroHandles->Free(handle);
118}
119
120void HAL_SetAnalogGyroParameters(HAL_GyroHandle handle,
121 double voltsPerDegreePerSecond, double offset,
122 int32_t center, int32_t* status) {
123 auto gyro = analogGyroHandles->Get(handle);
124 if (gyro == nullptr) {
125 *status = HAL_HANDLE_ERROR;
126 return;
127 }
128
129 gyro->voltsPerDegreePerSecond = voltsPerDegreePerSecond;
130 gyro->offset = offset;
131 gyro->center = center;
132 HAL_SetAccumulatorCenter(gyro->handle, center, status);
133}
134
135void HAL_SetAnalogGyroVoltsPerDegreePerSecond(HAL_GyroHandle handle,
136 double voltsPerDegreePerSecond,
137 int32_t* status) {
138 auto gyro = analogGyroHandles->Get(handle);
139 if (gyro == nullptr) {
140 *status = HAL_HANDLE_ERROR;
141 return;
142 }
143
144 gyro->voltsPerDegreePerSecond = voltsPerDegreePerSecond;
145}
146
147void HAL_ResetAnalogGyro(HAL_GyroHandle handle, int32_t* status) {
148 auto gyro = analogGyroHandles->Get(handle);
149 if (gyro == nullptr) {
150 *status = HAL_HANDLE_ERROR;
151 return;
152 }
153 HAL_ResetAccumulator(gyro->handle, status);
154 if (*status != 0) return;
155
156 const double sampleTime = 1.0 / HAL_GetAnalogSampleRate(status);
157 const double overSamples =
158 1 << HAL_GetAnalogOversampleBits(gyro->handle, status);
159 const double averageSamples =
160 1 << HAL_GetAnalogAverageBits(gyro->handle, status);
161 if (*status != 0) return;
162 Wait(sampleTime * overSamples * averageSamples);
163}
164
165void HAL_CalibrateAnalogGyro(HAL_GyroHandle handle, int32_t* status) {
166 auto gyro = analogGyroHandles->Get(handle);
167 if (gyro == nullptr) {
168 *status = HAL_HANDLE_ERROR;
169 return;
170 }
171
172 HAL_InitAccumulator(gyro->handle, status);
173 if (*status != 0) return;
174 wpi::outs() << "Calibrating analog gyro for " << kCalibrationSampleTime
175 << " seconds." << '\n';
176 Wait(kCalibrationSampleTime);
177
178 int64_t value;
179 int64_t count;
180 HAL_GetAccumulatorOutput(gyro->handle, &value, &count, status);
181 if (*status != 0) return;
182
183 gyro->center = static_cast<int32_t>(
184 static_cast<double>(value) / static_cast<double>(count) + 0.5);
185
186 gyro->offset = static_cast<double>(value) / static_cast<double>(count) -
187 static_cast<double>(gyro->center);
188 HAL_SetAccumulatorCenter(gyro->handle, gyro->center, status);
189 if (*status != 0) return;
190 HAL_ResetAnalogGyro(handle, status);
191}
192
193void HAL_SetAnalogGyroDeadband(HAL_GyroHandle handle, double volts,
194 int32_t* status) {
195 auto gyro = analogGyroHandles->Get(handle);
196 if (gyro == nullptr) {
197 *status = HAL_HANDLE_ERROR;
198 return;
199 }
200 int32_t deadband = static_cast<int32_t>(
201 volts * 1e9 / HAL_GetAnalogLSBWeight(gyro->handle, status) *
202 (1 << HAL_GetAnalogOversampleBits(gyro->handle, status)));
203 if (*status != 0) return;
204 HAL_SetAccumulatorDeadband(gyro->handle, deadband, status);
205}
206
207double HAL_GetAnalogGyroAngle(HAL_GyroHandle handle, int32_t* status) {
208 auto gyro = analogGyroHandles->Get(handle);
209 if (gyro == nullptr) {
210 *status = HAL_HANDLE_ERROR;
211 return 0;
212 }
213 int64_t rawValue = 0;
214 int64_t count = 0;
215 HAL_GetAccumulatorOutput(gyro->handle, &rawValue, &count, status);
216
217 int64_t value = rawValue - static_cast<int64_t>(static_cast<double>(count) *
218 gyro->offset);
219
220 double scaledValue =
221 value * 1e-9 *
222 static_cast<double>(HAL_GetAnalogLSBWeight(gyro->handle, status)) *
223 static_cast<double>(1 << HAL_GetAnalogAverageBits(gyro->handle, status)) /
224 (HAL_GetAnalogSampleRate(status) * gyro->voltsPerDegreePerSecond);
225
226 return scaledValue;
227}
228
229double HAL_GetAnalogGyroRate(HAL_GyroHandle handle, int32_t* status) {
230 auto gyro = analogGyroHandles->Get(handle);
231 if (gyro == nullptr) {
232 *status = HAL_HANDLE_ERROR;
233 return 0;
234 }
235
236 return (HAL_GetAnalogAverageValue(gyro->handle, status) -
237 (static_cast<double>(gyro->center) + gyro->offset)) *
238 1e-9 * HAL_GetAnalogLSBWeight(gyro->handle, status) /
239 ((1 << HAL_GetAnalogOversampleBits(gyro->handle, status)) *
240 gyro->voltsPerDegreePerSecond);
241}
242
243double HAL_GetAnalogGyroOffset(HAL_GyroHandle handle, int32_t* status) {
244 auto gyro = analogGyroHandles->Get(handle);
245 if (gyro == nullptr) {
246 *status = HAL_HANDLE_ERROR;
247 return 0;
248 }
249 return gyro->offset;
250}
251
252int32_t HAL_GetAnalogGyroCenter(HAL_GyroHandle handle, int32_t* status) {
253 auto gyro = analogGyroHandles->Get(handle);
254 if (gyro == nullptr) {
255 *status = HAL_HANDLE_ERROR;
256 return 0;
257 }
258 return gyro->center;
259}
260
261} // extern "C"