blob: d3e2cc6506739088d59fabe35d6433cd02e229c4 [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 "AnalogGyro.h"
9#include "HAL/AnalogGyro.h"
10
11#include <climits>
12
13#include "AnalogInput.h"
14#include "HAL/Errors.h"
15#include "HAL/HAL.h"
16#include "LiveWindow/LiveWindow.h"
17#include "Timer.h"
18#include "WPIErrors.h"
19
20using namespace frc;
21
22const int AnalogGyro::kOversampleBits;
23const int AnalogGyro::kAverageBits;
24constexpr double AnalogGyro::kSamplesPerSecond;
25constexpr double AnalogGyro::kCalibrationSampleTime;
26constexpr double AnalogGyro::kDefaultVoltsPerDegreePerSecond;
27
28/**
29 * Gyro constructor using the Analog Input channel number.
30 *
31 * @param channel The analog channel the gyro is connected to. Gyros can only
32 * be used on on-board Analog Inputs 0-1.
33 */
34AnalogGyro::AnalogGyro(int channel)
35 : AnalogGyro(std::make_shared<AnalogInput>(channel)) {}
36
37/**
38 * Gyro constructor with a precreated AnalogInput object.
39 *
40 * Use this constructor when the analog channel needs to be shared.
41 * This object will not clean up the AnalogInput object when using this
42 * constructor.
43 *
44 * Gyros can only be used on on-board channels 0-1.
45 *
46 * @param channel A pointer to the AnalogInput object that the gyro is
47 * connected to.
48 */
49AnalogGyro::AnalogGyro(AnalogInput* channel)
50 : AnalogGyro(
51 std::shared_ptr<AnalogInput>(channel, NullDeleter<AnalogInput>())) {}
52
53/**
54 * Gyro constructor with a precreated AnalogInput object.
55 *
56 * Use this constructor when the analog channel needs to be shared.
57 * This object will not clean up the AnalogInput object when using this
58 * constructor.
59 *
60 * @param channel A pointer to the AnalogInput object that the gyro is
61 * connected to.
62 */
63AnalogGyro::AnalogGyro(std::shared_ptr<AnalogInput> channel)
64 : m_analog(channel) {
65 if (channel == nullptr) {
66 wpi_setWPIError(NullParameter);
67 } else {
68 InitGyro();
69 Calibrate();
70 }
71}
72
73/**
74 * Gyro constructor using the Analog Input channel number with parameters for
75 * presetting the center and offset values. Bypasses calibration.
76 *
77 * @param channel The analog channel the gyro is connected to. Gyros can only
78 * be used on on-board Analog Inputs 0-1.
79 * @param center Preset uncalibrated value to use as the accumulator center
80 * value.
81 * @param offset Preset uncalibrated value to use as the gyro offset.
82 */
83AnalogGyro::AnalogGyro(int channel, int center, double offset) {
84 m_analog = std::make_shared<AnalogInput>(channel);
85 InitGyro();
86 int32_t status = 0;
87 HAL_SetAnalogGyroParameters(m_gyroHandle, kDefaultVoltsPerDegreePerSecond,
88 offset, center, &status);
89 if (status != 0) {
90 wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
91 m_gyroHandle = HAL_kInvalidHandle;
92 return;
93 }
94 Reset();
95}
96
97/**
98 * Gyro constructor with a precreated AnalogInput object and calibrated
99 * parameters.
100 *
101 * Use this constructor when the analog channel needs to be shared.
102 * This object will not clean up the AnalogInput object when using this
103 * constructor.
104 *
105 * @param channel A pointer to the AnalogInput object that the gyro is
106 * connected to.
107 */
108AnalogGyro::AnalogGyro(std::shared_ptr<AnalogInput> channel, int center,
109 double offset)
110 : m_analog(channel) {
111 if (channel == nullptr) {
112 wpi_setWPIError(NullParameter);
113 } else {
114 InitGyro();
115 int32_t status = 0;
116 HAL_SetAnalogGyroParameters(m_gyroHandle, kDefaultVoltsPerDegreePerSecond,
117 offset, center, &status);
118 if (status != 0) {
119 wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
120 m_gyroHandle = HAL_kInvalidHandle;
121 return;
122 }
123 Reset();
124 }
125}
126
127/**
128 * AnalogGyro Destructor
129 *
130 */
131AnalogGyro::~AnalogGyro() { HAL_FreeAnalogGyro(m_gyroHandle); }
132
133/**
134 * Reset the gyro.
135 *
136 * Resets the gyro to a heading of zero. This can be used if there is
137 * significant drift in the gyro and it needs to be recalibrated after it has
138 * been running.
139 */
140void AnalogGyro::Reset() {
141 if (StatusIsFatal()) return;
142 int32_t status = 0;
143 HAL_ResetAnalogGyro(m_gyroHandle, &status);
144 wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
145}
146
147/**
148 * Initialize the gyro. Calibration is handled by Calibrate().
149 */
150void AnalogGyro::InitGyro() {
151 if (StatusIsFatal()) return;
152 if (m_gyroHandle == HAL_kInvalidHandle) {
153 int32_t status = 0;
154 m_gyroHandle = HAL_InitializeAnalogGyro(m_analog->m_port, &status);
155 if (status == PARAMETER_OUT_OF_RANGE) {
156 wpi_setWPIErrorWithContext(ParameterOutOfRange,
157 " channel (must be accumulator channel)");
158 m_analog = nullptr;
159 m_gyroHandle = HAL_kInvalidHandle;
160 return;
161 }
162 if (status != 0) {
163 wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
164 m_analog = nullptr;
165 m_gyroHandle = HAL_kInvalidHandle;
166 return;
167 }
168 }
169
170 int32_t status = 0;
171 HAL_SetupAnalogGyro(m_gyroHandle, &status);
172 if (status != 0) {
173 wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
174 m_analog = nullptr;
175 m_gyroHandle = HAL_kInvalidHandle;
176 return;
177 }
178
179 HAL_Report(HALUsageReporting::kResourceType_Gyro, m_analog->GetChannel());
180 LiveWindow::GetInstance()->AddSensor("AnalogGyro", m_analog->GetChannel(),
181 this);
182}
183
184void AnalogGyro::Calibrate() {
185 if (StatusIsFatal()) return;
186 int32_t status = 0;
187 HAL_CalibrateAnalogGyro(m_gyroHandle, &status);
188 wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
189}
190
191/**
192 * Return the actual angle in degrees that the robot is currently facing.
193 *
194 * The angle is based on the current accumulator value corrected by the
195 * oversampling rate, the gyro type and the A/D calibration values.
196 * The angle is continuous, that is it will continue from 360->361 degrees. This
197 * allows algorithms that wouldn't want to see a discontinuity in the gyro
198 * output as it sweeps from 360 to 0 on the second time around.
199 *
200 * @return the current heading of the robot in degrees. This heading is based on
201 * integration of the returned rate from the gyro.
202 */
203double AnalogGyro::GetAngle() const {
204 if (StatusIsFatal()) return 0.0;
205 int32_t status = 0;
206 double value = HAL_GetAnalogGyroAngle(m_gyroHandle, &status);
207 wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
208 return value;
209}
210
211/**
212 * Return the rate of rotation of the gyro
213 *
214 * The rate is based on the most recent reading of the gyro analog value
215 *
216 * @return the current rate in degrees per second
217 */
218double AnalogGyro::GetRate() const {
219 if (StatusIsFatal()) return 0.0;
220 int32_t status = 0;
221 double value = HAL_GetAnalogGyroRate(m_gyroHandle, &status);
222 wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
223 return value;
224}
225
226/**
227 * Return the gyro offset value. If run after calibration,
228 * the offset value can be used as a preset later.
229 *
230 * @return the current offset value
231 */
232double AnalogGyro::GetOffset() const {
233 if (StatusIsFatal()) return 0.0;
234 int32_t status = 0;
235 double value = HAL_GetAnalogGyroOffset(m_gyroHandle, &status);
236 wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
237 return value;
238}
239
240/**
241 * Return the gyro center value. If run after calibration,
242 * the center value can be used as a preset later.
243 *
244 * @return the current center value
245 */
246int AnalogGyro::GetCenter() const {
247 if (StatusIsFatal()) return 0;
248 int32_t status = 0;
249 int value = HAL_GetAnalogGyroCenter(m_gyroHandle, &status);
250 wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
251 return value;
252}
253
254/**
255 * Set the gyro sensitivity.
256 *
257 * This takes the number of volts/degree/second sensitivity of the gyro and uses
258 * it in subsequent calculations to allow the code to work with multiple gyros.
259 * This value is typically found in the gyro datasheet.
260 *
261 * @param voltsPerDegreePerSecond The sensitivity in Volts/degree/second
262 */
263void AnalogGyro::SetSensitivity(double voltsPerDegreePerSecond) {
264 int32_t status = 0;
265 HAL_SetAnalogGyroVoltsPerDegreePerSecond(m_gyroHandle,
266 voltsPerDegreePerSecond, &status);
267 wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
268}
269
270/**
271 * Set the size of the neutral zone.
272 *
273 * Any voltage from the gyro less than this amount from the center is
274 * considered stationary. Setting a deadband will decrease the amount of drift
275 * when the gyro isn't rotating, but will make it less accurate.
276 *
277 * @param volts The size of the deadband in volts
278 */
279void AnalogGyro::SetDeadband(double volts) {
280 if (StatusIsFatal()) return;
281 int32_t status = 0;
282 HAL_SetAnalogGyroDeadband(m_gyroHandle, volts, &status);
283 wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
284}