Brian Silverman | 26e4e52 | 2015-12-17 01:56:40 -0500 | [diff] [blame^] | 1 | /*----------------------------------------------------------------------------*/ |
| 2 | /* Copyright (c) FIRST 2008. All Rights Reserved. |
| 3 | */ |
| 4 | /* Open Source Software - may be modified and shared by FRC teams. The code */ |
| 5 | /* must be accompanied by the FIRST BSD license file in $(WIND_BASE)/WPILib. */ |
| 6 | /*----------------------------------------------------------------------------*/ |
| 7 | |
| 8 | #include "AnalogGyro.h" |
| 9 | #include "AnalogInput.h" |
| 10 | #include "Timer.h" |
| 11 | #include "WPIErrors.h" |
| 12 | #include "LiveWindow/LiveWindow.h" |
| 13 | #include <climits> |
| 14 | const uint32_t AnalogGyro::kOversampleBits; |
| 15 | const uint32_t AnalogGyro::kAverageBits; |
| 16 | constexpr float AnalogGyro::kSamplesPerSecond; |
| 17 | constexpr float AnalogGyro::kCalibrationSampleTime; |
| 18 | constexpr float AnalogGyro::kDefaultVoltsPerDegreePerSecond; |
| 19 | |
| 20 | /** |
| 21 | * Gyro constructor using the Analog Input channel number. |
| 22 | * |
| 23 | * @param channel The analog channel the gyro is connected to. Gyros |
| 24 | can only be used on on-board Analog Inputs 0-1. |
| 25 | */ |
| 26 | AnalogGyro::AnalogGyro(int32_t channel) : |
| 27 | AnalogGyro(std::make_shared<AnalogInput>(channel)) {} |
| 28 | |
| 29 | /** |
| 30 | * Gyro constructor with a precreated AnalogInput object. |
| 31 | * Use this constructor when the analog channel needs to be shared. |
| 32 | * This object will not clean up the AnalogInput object when using this |
| 33 | * constructor. |
| 34 | * Gyros can only be used on on-board channels 0-1. |
| 35 | * @param channel A pointer to the AnalogInput object that the gyro is connected |
| 36 | * to. |
| 37 | */ |
| 38 | AnalogGyro::AnalogGyro(AnalogInput *channel) |
| 39 | : AnalogGyro( |
| 40 | std::shared_ptr<AnalogInput>(channel, NullDeleter<AnalogInput>())) {} |
| 41 | |
| 42 | /** |
| 43 | * Gyro constructor with a precreated AnalogInput object. |
| 44 | * Use this constructor when the analog channel needs to be shared. |
| 45 | * This object will not clean up the AnalogInput object when using this |
| 46 | * constructor |
| 47 | * @param channel A pointer to the AnalogInput object that the gyro is |
| 48 | * connected to. |
| 49 | */ |
| 50 | AnalogGyro::AnalogGyro(std::shared_ptr<AnalogInput> channel) |
| 51 | : m_analog(channel) { |
| 52 | if (channel == nullptr) { |
| 53 | wpi_setWPIError(NullParameter); |
| 54 | } else { |
| 55 | InitGyro(); |
| 56 | Calibrate(); |
| 57 | } |
| 58 | } |
| 59 | |
| 60 | /** |
| 61 | * Gyro constructor using the Analog Input channel number with parameters for |
| 62 | * presetting the center and offset values. Bypasses calibration. |
| 63 | * |
| 64 | * @param channel The analog channel the gyro is connected to. Gyros |
| 65 | * can only be used on on-board Analog Inputs 0-1. |
| 66 | * @param center Preset uncalibrated value to use as the accumulator center value. |
| 67 | * @param offset Preset uncalibrated value to use as the gyro offset. |
| 68 | */ |
| 69 | AnalogGyro::AnalogGyro(int32_t channel, uint32_t center, float offset) { |
| 70 | m_analog = std::make_shared<AnalogInput>(channel); |
| 71 | InitGyro(); |
| 72 | m_center = center; |
| 73 | m_offset = offset; |
| 74 | m_analog->SetAccumulatorCenter(m_center); |
| 75 | m_analog->ResetAccumulator(); |
| 76 | } |
| 77 | |
| 78 | /** |
| 79 | * Gyro constructor with a precreated AnalogInput object and calibrated parameters. |
| 80 | * Use this constructor when the analog channel needs to be shared. |
| 81 | * This object will not clean up the AnalogInput object when using this |
| 82 | * constructor |
| 83 | * @param channel A pointer to the AnalogInput object that the gyro is |
| 84 | * connected to. |
| 85 | */ |
| 86 | AnalogGyro::AnalogGyro(std::shared_ptr<AnalogInput> channel, uint32_t center, float offset) : m_analog(channel) { |
| 87 | if (channel == nullptr) { |
| 88 | wpi_setWPIError(NullParameter); |
| 89 | } else { |
| 90 | InitGyro(); |
| 91 | m_center = center; |
| 92 | m_offset = offset; |
| 93 | m_analog->SetAccumulatorCenter(m_center); |
| 94 | m_analog->ResetAccumulator(); |
| 95 | } |
| 96 | } |
| 97 | |
| 98 | /** |
| 99 | * Reset the gyro. |
| 100 | * Resets the gyro to a heading of zero. This can be used if there is |
| 101 | * significant |
| 102 | * drift in the gyro and it needs to be recalibrated after it has been running. |
| 103 | */ |
| 104 | void AnalogGyro::Reset() { |
| 105 | if (StatusIsFatal()) return; |
| 106 | m_analog->ResetAccumulator(); |
| 107 | } |
| 108 | |
| 109 | /** |
| 110 | * Initialize the gyro. Calibration is handled by Calibrate(). |
| 111 | */ |
| 112 | void AnalogGyro::InitGyro() { |
| 113 | if (StatusIsFatal()) return; |
| 114 | |
| 115 | if (!m_analog->IsAccumulatorChannel()) { |
| 116 | wpi_setWPIErrorWithContext(ParameterOutOfRange, |
| 117 | " channel (must be accumulator channel)"); |
| 118 | m_analog = nullptr; |
| 119 | return; |
| 120 | } |
| 121 | |
| 122 | m_voltsPerDegreePerSecond = kDefaultVoltsPerDegreePerSecond; |
| 123 | m_analog->SetAverageBits(kAverageBits); |
| 124 | m_analog->SetOversampleBits(kOversampleBits); |
| 125 | float sampleRate = |
| 126 | kSamplesPerSecond * (1 << (kAverageBits + kOversampleBits)); |
| 127 | m_analog->SetSampleRate(sampleRate); |
| 128 | Wait(0.1); |
| 129 | |
| 130 | SetDeadband(0.0f); |
| 131 | |
| 132 | SetPIDSourceType(PIDSourceType::kDisplacement); |
| 133 | |
| 134 | HALReport(HALUsageReporting::kResourceType_Gyro, m_analog->GetChannel()); |
| 135 | LiveWindow::GetInstance()->AddSensor("Gyro", m_analog->GetChannel(), this); |
| 136 | } |
| 137 | |
| 138 | /** |
| 139 | * {@inheritDoc} |
| 140 | */ |
| 141 | void AnalogGyro::Calibrate() { |
| 142 | if (StatusIsFatal()) return; |
| 143 | |
| 144 | m_analog->InitAccumulator(); |
| 145 | |
| 146 | Wait(kCalibrationSampleTime); |
| 147 | |
| 148 | int64_t value; |
| 149 | uint32_t count; |
| 150 | m_analog->GetAccumulatorOutput(value, count); |
| 151 | |
| 152 | m_center = (uint32_t)((float)value / (float)count + .5); |
| 153 | |
| 154 | m_offset = ((float)value / (float)count) - (float)m_center; |
| 155 | m_analog->SetAccumulatorCenter(m_center); |
| 156 | m_analog->ResetAccumulator(); |
| 157 | } |
| 158 | |
| 159 | /** |
| 160 | * Return the actual angle in degrees that the robot is currently facing. |
| 161 | * |
| 162 | * The angle is based on the current accumulator value corrected by the |
| 163 | * oversampling rate, the |
| 164 | * gyro type and the A/D calibration values. |
| 165 | * The angle is continuous, that is it will continue from 360->361 degrees. This |
| 166 | * allows algorithms that wouldn't |
| 167 | * want to see a discontinuity in the gyro output as it sweeps from 360 to 0 on |
| 168 | * the second time around. |
| 169 | * |
| 170 | * @return the current heading of the robot in degrees. This heading is based on |
| 171 | * integration |
| 172 | * of the returned rate from the gyro. |
| 173 | */ |
| 174 | float AnalogGyro::GetAngle() const { |
| 175 | if (StatusIsFatal()) return 0.f; |
| 176 | |
| 177 | int64_t rawValue; |
| 178 | uint32_t count; |
| 179 | m_analog->GetAccumulatorOutput(rawValue, count); |
| 180 | |
| 181 | int64_t value = rawValue - (int64_t)((float)count * m_offset); |
| 182 | |
| 183 | double scaledValue = value * 1e-9 * (double)m_analog->GetLSBWeight() * |
| 184 | (double)(1 << m_analog->GetAverageBits()) / |
| 185 | (m_analog->GetSampleRate() * m_voltsPerDegreePerSecond); |
| 186 | |
| 187 | return (float)scaledValue; |
| 188 | } |
| 189 | |
| 190 | /** |
| 191 | * Return the rate of rotation of the gyro |
| 192 | * |
| 193 | * The rate is based on the most recent reading of the gyro analog value |
| 194 | * |
| 195 | * @return the current rate in degrees per second |
| 196 | */ |
| 197 | double AnalogGyro::GetRate() const { |
| 198 | if (StatusIsFatal()) return 0.0; |
| 199 | |
| 200 | return (m_analog->GetAverageValue() - ((double)m_center + m_offset)) * 1e-9 * |
| 201 | m_analog->GetLSBWeight() / |
| 202 | ((1 << m_analog->GetOversampleBits()) * m_voltsPerDegreePerSecond); |
| 203 | } |
| 204 | |
| 205 | /** |
| 206 | * Return the gyro offset value. If run after calibration, |
| 207 | * the offset value can be used as a preset later. |
| 208 | * |
| 209 | * @return the current offset value |
| 210 | */ |
| 211 | float AnalogGyro::GetOffset() const { |
| 212 | return m_offset; |
| 213 | } |
| 214 | |
| 215 | /** |
| 216 | * Return the gyro center value. If run after calibration, |
| 217 | * the center value can be used as a preset later. |
| 218 | * |
| 219 | * @return the current center value |
| 220 | */ |
| 221 | uint32_t AnalogGyro::GetCenter() const { |
| 222 | return m_center; |
| 223 | } |
| 224 | |
| 225 | /** |
| 226 | * Set the gyro sensitivity. |
| 227 | * This takes the number of volts/degree/second sensitivity of the gyro and uses |
| 228 | * it in subsequent |
| 229 | * calculations to allow the code to work with multiple gyros. This value is |
| 230 | * typically found in |
| 231 | * the gyro datasheet. |
| 232 | * |
| 233 | * @param voltsPerDegreePerSecond The sensitivity in Volts/degree/second |
| 234 | */ |
| 235 | void AnalogGyro::SetSensitivity(float voltsPerDegreePerSecond) { |
| 236 | m_voltsPerDegreePerSecond = voltsPerDegreePerSecond; |
| 237 | } |
| 238 | |
| 239 | /** |
| 240 | * Set the size of the neutral zone. Any voltage from the gyro less than this |
| 241 | * amount from the center is considered stationary. Setting a deadband will |
| 242 | * decrease the amount of drift when the gyro isn't rotating, but will make it |
| 243 | * less accurate. |
| 244 | * |
| 245 | * @param volts The size of the deadband in volts |
| 246 | */ |
| 247 | void AnalogGyro::SetDeadband(float volts) { |
| 248 | if (StatusIsFatal()) return; |
| 249 | |
| 250 | int32_t deadband = volts * 1e9 / m_analog->GetLSBWeight() * |
| 251 | (1 << m_analog->GetOversampleBits()); |
| 252 | m_analog->SetAccumulatorDeadband(deadband); |
| 253 | } |
| 254 | |
| 255 | std::string AnalogGyro::GetSmartDashboardType() const { return "AnalogGyro"; } |