Brian Silverman | 26e4e52 | 2015-12-17 01:56:40 -0500 | [diff] [blame] | 1 | /*----------------------------------------------------------------------------*/ |
Brian Silverman | 1a67511 | 2016-02-20 20:42:49 -0500 | [diff] [blame^] | 2 | /* Copyright (c) FIRST 2008-2016. All Rights Reserved. */ |
Brian Silverman | 26e4e52 | 2015-12-17 01:56:40 -0500 | [diff] [blame] | 3 | /* Open Source Software - may be modified and shared by FRC teams. The code */ |
Brian Silverman | 1a67511 | 2016-02-20 20:42:49 -0500 | [diff] [blame^] | 4 | /* must be accompanied by the FIRST BSD license file in the root directory of */ |
| 5 | /* the project. */ |
Brian Silverman | 26e4e52 | 2015-12-17 01:56:40 -0500 | [diff] [blame] | 6 | /*----------------------------------------------------------------------------*/ |
| 7 | |
| 8 | #include "Counter.h" |
| 9 | #include "AnalogTrigger.h" |
| 10 | #include "DigitalInput.h" |
| 11 | #include "Resource.h" |
| 12 | #include "WPIErrors.h" |
| 13 | |
| 14 | /** |
| 15 | * Create an instance of a counter where no sources are selected. |
| 16 | * They all must be selected by calling functions to specify the upsource and |
| 17 | * the downsource |
| 18 | * independently. |
| 19 | * |
| 20 | * This creates a ChipObject counter and initializes status variables |
| 21 | * appropriately. |
| 22 | * |
| 23 | * The counter will start counting immediately. |
| 24 | * @param mode The counter mode |
| 25 | */ |
| 26 | Counter::Counter(Mode mode) { |
| 27 | int32_t status = 0; |
| 28 | m_counter = initializeCounter(mode, &m_index, &status); |
| 29 | wpi_setErrorWithContext(status, getHALErrorMessage(status)); |
| 30 | |
| 31 | SetMaxPeriod(.5); |
| 32 | |
| 33 | HALReport(HALUsageReporting::kResourceType_Counter, m_index, mode); |
| 34 | } |
| 35 | |
| 36 | /** |
| 37 | * Create an instance of a counter from a Digital Source (such as a Digital |
| 38 | * Input). |
| 39 | * This is used if an existing digital input is to be shared by multiple other |
| 40 | * objects such |
| 41 | * as encoders or if the Digital Source is not a Digital Input channel (such as |
| 42 | * an Analog Trigger). |
| 43 | * |
| 44 | * The counter will start counting immediately. |
| 45 | * @param source A pointer to the existing DigitalSource object. It will be set |
| 46 | * as the Up Source. |
| 47 | */ |
| 48 | Counter::Counter(DigitalSource *source) : Counter(kTwoPulse) { |
| 49 | SetUpSource(source); |
| 50 | ClearDownSource(); |
| 51 | } |
| 52 | |
| 53 | /** |
| 54 | * Create an instance of a counter from a Digital Source (such as a Digital |
| 55 | * Input). |
| 56 | * This is used if an existing digital input is to be shared by multiple other |
| 57 | * objects such |
| 58 | * as encoders or if the Digital Source is not a Digital Input channel (such as |
| 59 | * an Analog Trigger). |
| 60 | * |
| 61 | * The counter will start counting immediately. |
| 62 | * @param source A pointer to the existing DigitalSource object. It will be |
| 63 | * set as the Up Source. |
| 64 | */ |
| 65 | Counter::Counter(std::shared_ptr<DigitalSource> source) : Counter(kTwoPulse) { |
| 66 | SetUpSource(source); |
| 67 | ClearDownSource(); |
| 68 | } |
| 69 | |
| 70 | /** |
| 71 | * Create an instance of a Counter object. |
| 72 | * Create an up-Counter instance given a channel. |
| 73 | * |
| 74 | * The counter will start counting immediately. |
| 75 | * @param channel The DIO channel to use as the up source. 0-9 are on-board, |
| 76 | * 10-25 are on the MXP |
| 77 | */ |
| 78 | Counter::Counter(int32_t channel) : Counter(kTwoPulse) { |
| 79 | SetUpSource(channel); |
| 80 | ClearDownSource(); |
| 81 | } |
| 82 | |
| 83 | /** |
| 84 | * Create an instance of a Counter object. |
| 85 | * Create an instance of a simple up-Counter given an analog trigger. |
| 86 | * Use the trigger state output from the analog trigger. |
| 87 | * |
| 88 | * The counter will start counting immediately. |
| 89 | * @param trigger The pointer to the existing AnalogTrigger object. |
| 90 | */ |
| 91 | DEPRECATED("Use pass-by-reference instead.") |
| 92 | Counter::Counter(AnalogTrigger *trigger) : Counter(kTwoPulse) { |
| 93 | SetUpSource(trigger->CreateOutput(kState)); |
| 94 | ClearDownSource(); |
| 95 | } |
| 96 | |
| 97 | /** |
| 98 | * Create an instance of a Counter object. |
| 99 | * Create an instance of a simple up-Counter given an analog trigger. |
| 100 | * Use the trigger state output from the analog trigger. |
| 101 | * |
| 102 | * The counter will start counting immediately. |
| 103 | * @param trigger The reference to the existing AnalogTrigger object. |
| 104 | */ |
| 105 | Counter::Counter(const AnalogTrigger &trigger) : Counter(kTwoPulse) { |
| 106 | SetUpSource(trigger.CreateOutput(kState)); |
| 107 | ClearDownSource(); |
| 108 | } |
| 109 | |
| 110 | /** |
| 111 | * Create an instance of a Counter object. |
| 112 | * Creates a full up-down counter given two Digital Sources |
| 113 | * @param encodingType The quadrature decoding mode (1x or 2x) |
| 114 | * @param upSource The pointer to the DigitalSource to set as the up source |
| 115 | * @param downSource The pointer to the DigitalSource to set as the down source |
| 116 | * @param inverted True to invert the output (reverse the direction) |
| 117 | */ |
| 118 | Counter::Counter(EncodingType encodingType, DigitalSource *upSource, |
| 119 | DigitalSource *downSource, bool inverted) |
| 120 | : Counter(encodingType, |
| 121 | std::shared_ptr<DigitalSource>(upSource, |
| 122 | NullDeleter<DigitalSource>()), |
| 123 | std::shared_ptr<DigitalSource>(downSource, |
| 124 | NullDeleter<DigitalSource>()), |
| 125 | inverted) {} |
| 126 | |
| 127 | /** |
| 128 | * Create an instance of a Counter object. |
| 129 | * Creates a full up-down counter given two Digital Sources |
| 130 | * @param encodingType The quadrature decoding mode (1x or 2x) |
| 131 | * @param upSource The pointer to the DigitalSource to set as the up source |
| 132 | * @param downSource The pointer to the DigitalSource to set as the down source |
| 133 | * @param inverted True to invert the output (reverse the direction) |
| 134 | */ |
| 135 | Counter::Counter(EncodingType encodingType, |
| 136 | std::shared_ptr<DigitalSource> upSource, |
| 137 | std::shared_ptr<DigitalSource> downSource, bool inverted) |
| 138 | : Counter(kExternalDirection) { |
| 139 | if (encodingType != k1X && encodingType != k2X) { |
| 140 | wpi_setWPIErrorWithContext( |
| 141 | ParameterOutOfRange, |
| 142 | "Counter only supports 1X and 2X quadrature decoding."); |
| 143 | return; |
| 144 | } |
| 145 | SetUpSource(upSource); |
| 146 | SetDownSource(downSource); |
| 147 | int32_t status = 0; |
| 148 | |
| 149 | if (encodingType == k1X) { |
| 150 | SetUpSourceEdge(true, false); |
| 151 | setCounterAverageSize(m_counter, 1, &status); |
| 152 | } else { |
| 153 | SetUpSourceEdge(true, true); |
| 154 | setCounterAverageSize(m_counter, 2, &status); |
| 155 | } |
| 156 | |
| 157 | wpi_setErrorWithContext(status, getHALErrorMessage(status)); |
| 158 | SetDownSourceEdge(inverted, true); |
| 159 | } |
| 160 | |
| 161 | /** |
| 162 | * Delete the Counter object. |
| 163 | */ |
| 164 | Counter::~Counter() { |
| 165 | SetUpdateWhenEmpty(true); |
| 166 | |
| 167 | int32_t status = 0; |
| 168 | freeCounter(m_counter, &status); |
| 169 | wpi_setErrorWithContext(status, getHALErrorMessage(status)); |
| 170 | m_counter = nullptr; |
| 171 | } |
| 172 | |
| 173 | /** |
| 174 | * Set the upsource for the counter as a digital input channel. |
| 175 | * @param channel The DIO channel to use as the up source. 0-9 are on-board, |
| 176 | * 10-25 are on the MXP |
| 177 | */ |
| 178 | void Counter::SetUpSource(int32_t channel) { |
| 179 | if (StatusIsFatal()) return; |
| 180 | SetUpSource(std::make_shared<DigitalInput>(channel)); |
| 181 | } |
| 182 | |
| 183 | /** |
| 184 | * Set the up counting source to be an analog trigger. |
| 185 | * @param analogTrigger The analog trigger object that is used for the Up Source |
| 186 | * @param triggerType The analog trigger output that will trigger the counter. |
| 187 | */ |
| 188 | void Counter::SetUpSource(AnalogTrigger *analogTrigger, |
| 189 | AnalogTriggerType triggerType) { |
| 190 | SetUpSource(std::shared_ptr<AnalogTrigger>(analogTrigger, |
| 191 | NullDeleter<AnalogTrigger>()), |
| 192 | triggerType); |
| 193 | } |
| 194 | |
| 195 | /** |
| 196 | * Set the up counting source to be an analog trigger. |
| 197 | * @param analogTrigger The analog trigger object that is used for the Up Source |
| 198 | * @param triggerType The analog trigger output that will trigger the counter. |
| 199 | */ |
| 200 | void Counter::SetUpSource(std::shared_ptr<AnalogTrigger> analogTrigger, |
| 201 | AnalogTriggerType triggerType) { |
| 202 | if (StatusIsFatal()) return; |
| 203 | SetUpSource(analogTrigger->CreateOutput(triggerType)); |
| 204 | } |
| 205 | |
| 206 | /** |
| 207 | * Set the source object that causes the counter to count up. |
| 208 | * Set the up counting DigitalSource. |
| 209 | * @param source Pointer to the DigitalSource object to set as the up source |
| 210 | */ |
| 211 | void Counter::SetUpSource(std::shared_ptr<DigitalSource> source) { |
| 212 | if (StatusIsFatal()) return; |
| 213 | m_upSource = source; |
| 214 | if (m_upSource->StatusIsFatal()) { |
| 215 | CloneError(*m_upSource); |
| 216 | } else { |
| 217 | int32_t status = 0; |
| 218 | setCounterUpSource(m_counter, source->GetChannelForRouting(), |
| 219 | source->GetAnalogTriggerForRouting(), &status); |
| 220 | wpi_setErrorWithContext(status, getHALErrorMessage(status)); |
| 221 | } |
| 222 | } |
| 223 | |
| 224 | void Counter::SetUpSource(DigitalSource *source) { |
| 225 | SetUpSource( |
| 226 | std::shared_ptr<DigitalSource>(source, NullDeleter<DigitalSource>())); |
| 227 | } |
| 228 | |
| 229 | /** |
| 230 | * Set the source object that causes the counter to count up. |
| 231 | * Set the up counting DigitalSource. |
| 232 | * @param source Reference to the DigitalSource object to set as the up source |
| 233 | */ |
| 234 | void Counter::SetUpSource(DigitalSource &source) { |
| 235 | SetUpSource( |
| 236 | std::shared_ptr<DigitalSource>(&source, NullDeleter<DigitalSource>())); |
| 237 | } |
| 238 | |
| 239 | /** |
| 240 | * Set the edge sensitivity on an up counting source. |
| 241 | * Set the up source to either detect rising edges or falling edges or both. |
| 242 | * @param risingEdge True to trigger on rising edges |
| 243 | * @param fallingEdge True to trigger on falling edges |
| 244 | */ |
| 245 | void Counter::SetUpSourceEdge(bool risingEdge, bool fallingEdge) { |
| 246 | if (StatusIsFatal()) return; |
| 247 | if (m_upSource == nullptr) { |
| 248 | wpi_setWPIErrorWithContext( |
| 249 | NullParameter, |
| 250 | "Must set non-nullptr UpSource before setting UpSourceEdge"); |
| 251 | } |
| 252 | int32_t status = 0; |
| 253 | setCounterUpSourceEdge(m_counter, risingEdge, fallingEdge, &status); |
| 254 | wpi_setErrorWithContext(status, getHALErrorMessage(status)); |
| 255 | } |
| 256 | |
| 257 | /** |
| 258 | * Disable the up counting source to the counter. |
| 259 | */ |
| 260 | void Counter::ClearUpSource() { |
| 261 | if (StatusIsFatal()) return; |
| 262 | m_upSource.reset(); |
| 263 | int32_t status = 0; |
| 264 | clearCounterUpSource(m_counter, &status); |
| 265 | wpi_setErrorWithContext(status, getHALErrorMessage(status)); |
| 266 | } |
| 267 | |
| 268 | /** |
| 269 | * Set the down counting source to be a digital input channel. |
| 270 | * @param channel The DIO channel to use as the up source. 0-9 are on-board, |
| 271 | * 10-25 are on the MXP |
| 272 | */ |
| 273 | void Counter::SetDownSource(int32_t channel) { |
| 274 | if (StatusIsFatal()) return; |
| 275 | SetDownSource(std::make_shared<DigitalInput>(channel)); |
| 276 | } |
| 277 | |
| 278 | /** |
| 279 | * Set the down counting source to be an analog trigger. |
| 280 | * @param analogTrigger The analog trigger object that is used for the Down |
| 281 | * Source |
| 282 | * @param triggerType The analog trigger output that will trigger the counter. |
| 283 | */ |
| 284 | void Counter::SetDownSource(AnalogTrigger *analogTrigger, |
| 285 | AnalogTriggerType triggerType) { |
| 286 | SetDownSource(std::shared_ptr<AnalogTrigger>(analogTrigger, NullDeleter<AnalogTrigger>()), triggerType); |
| 287 | } |
| 288 | |
| 289 | /** |
| 290 | * Set the down counting source to be an analog trigger. |
| 291 | * @param analogTrigger The analog trigger object that is used for the Down |
| 292 | * Source |
| 293 | * @param triggerType The analog trigger output that will trigger the counter. |
| 294 | */ |
| 295 | void Counter::SetDownSource(std::shared_ptr<AnalogTrigger> analogTrigger, |
| 296 | AnalogTriggerType triggerType) { |
| 297 | if (StatusIsFatal()) return; |
| 298 | SetDownSource(analogTrigger->CreateOutput(triggerType)); |
| 299 | } |
| 300 | |
| 301 | /** |
| 302 | * Set the source object that causes the counter to count down. |
| 303 | * Set the down counting DigitalSource. |
| 304 | * @param source Pointer to the DigitalSource object to set as the down source |
| 305 | */ |
| 306 | void Counter::SetDownSource(std::shared_ptr<DigitalSource> source) { |
| 307 | if (StatusIsFatal()) return; |
| 308 | m_downSource = source; |
| 309 | if (m_downSource->StatusIsFatal()) { |
| 310 | CloneError(*m_downSource); |
| 311 | } else { |
| 312 | int32_t status = 0; |
| 313 | setCounterDownSource(m_counter, source->GetChannelForRouting(), |
| 314 | source->GetAnalogTriggerForRouting(), &status); |
| 315 | wpi_setErrorWithContext(status, getHALErrorMessage(status)); |
| 316 | } |
| 317 | } |
| 318 | |
| 319 | void Counter::SetDownSource(DigitalSource *source) { |
| 320 | SetDownSource(std::shared_ptr<DigitalSource>(source, NullDeleter<DigitalSource>())); |
| 321 | } |
| 322 | |
| 323 | /** |
| 324 | * Set the source object that causes the counter to count down. |
| 325 | * Set the down counting DigitalSource. |
| 326 | * @param source Reference to the DigitalSource object to set as the down source |
| 327 | */ |
| 328 | void Counter::SetDownSource(DigitalSource &source) { |
| 329 | SetDownSource(std::shared_ptr<DigitalSource>(&source, NullDeleter<DigitalSource>())); |
| 330 | } |
| 331 | |
| 332 | /** |
| 333 | * Set the edge sensitivity on a down counting source. |
| 334 | * Set the down source to either detect rising edges or falling edges. |
| 335 | * @param risingEdge True to trigger on rising edges |
| 336 | * @param fallingEdge True to trigger on falling edges |
| 337 | */ |
| 338 | void Counter::SetDownSourceEdge(bool risingEdge, bool fallingEdge) { |
| 339 | if (StatusIsFatal()) return; |
| 340 | if (m_downSource == nullptr) { |
| 341 | wpi_setWPIErrorWithContext( |
| 342 | NullParameter, |
| 343 | "Must set non-nullptr DownSource before setting DownSourceEdge"); |
| 344 | } |
| 345 | int32_t status = 0; |
| 346 | setCounterDownSourceEdge(m_counter, risingEdge, fallingEdge, &status); |
| 347 | wpi_setErrorWithContext(status, getHALErrorMessage(status)); |
| 348 | } |
| 349 | |
| 350 | /** |
| 351 | * Disable the down counting source to the counter. |
| 352 | */ |
| 353 | void Counter::ClearDownSource() { |
| 354 | if (StatusIsFatal()) return; |
| 355 | m_downSource.reset(); |
| 356 | int32_t status = 0; |
| 357 | clearCounterDownSource(m_counter, &status); |
| 358 | wpi_setErrorWithContext(status, getHALErrorMessage(status)); |
| 359 | } |
| 360 | |
| 361 | /** |
| 362 | * Set standard up / down counting mode on this counter. |
| 363 | * Up and down counts are sourced independently from two inputs. |
| 364 | */ |
| 365 | void Counter::SetUpDownCounterMode() { |
| 366 | if (StatusIsFatal()) return; |
| 367 | int32_t status = 0; |
| 368 | setCounterUpDownMode(m_counter, &status); |
| 369 | wpi_setErrorWithContext(status, getHALErrorMessage(status)); |
| 370 | } |
| 371 | |
| 372 | /** |
| 373 | * Set external direction mode on this counter. |
| 374 | * Counts are sourced on the Up counter input. |
| 375 | * The Down counter input represents the direction to count. |
| 376 | */ |
| 377 | void Counter::SetExternalDirectionMode() { |
| 378 | if (StatusIsFatal()) return; |
| 379 | int32_t status = 0; |
| 380 | setCounterExternalDirectionMode(m_counter, &status); |
| 381 | wpi_setErrorWithContext(status, getHALErrorMessage(status)); |
| 382 | } |
| 383 | |
| 384 | /** |
| 385 | * Set Semi-period mode on this counter. |
| 386 | * Counts up on both rising and falling edges. |
| 387 | */ |
| 388 | void Counter::SetSemiPeriodMode(bool highSemiPeriod) { |
| 389 | if (StatusIsFatal()) return; |
| 390 | int32_t status = 0; |
| 391 | setCounterSemiPeriodMode(m_counter, highSemiPeriod, &status); |
| 392 | wpi_setErrorWithContext(status, getHALErrorMessage(status)); |
| 393 | } |
| 394 | |
| 395 | /** |
| 396 | * Configure the counter to count in up or down based on the length of the input |
| 397 | * pulse. |
| 398 | * This mode is most useful for direction sensitive gear tooth sensors. |
| 399 | * @param threshold The pulse length beyond which the counter counts the |
| 400 | * opposite direction. Units are seconds. |
| 401 | */ |
| 402 | void Counter::SetPulseLengthMode(float threshold) { |
| 403 | if (StatusIsFatal()) return; |
| 404 | int32_t status = 0; |
| 405 | setCounterPulseLengthMode(m_counter, threshold, &status); |
| 406 | wpi_setErrorWithContext(status, getHALErrorMessage(status)); |
| 407 | } |
| 408 | |
| 409 | /** |
| 410 | * Get the Samples to Average which specifies the number of samples of the timer |
| 411 | * to |
| 412 | * average when calculating the period. Perform averaging to account for |
| 413 | * mechanical imperfections or as oversampling to increase resolution. |
| 414 | * @return SamplesToAverage The number of samples being averaged (from 1 to 127) |
| 415 | */ |
| 416 | int Counter::GetSamplesToAverage() const { |
| 417 | int32_t status = 0; |
| 418 | int32_t samples = getCounterSamplesToAverage(m_counter, &status); |
| 419 | wpi_setErrorWithContext(status, getHALErrorMessage(status)); |
| 420 | return samples; |
| 421 | } |
| 422 | |
| 423 | /** |
| 424 | * Set the Samples to Average which specifies the number of samples of the timer |
| 425 | * to |
| 426 | * average when calculating the period. Perform averaging to account for |
| 427 | * mechanical imperfections or as oversampling to increase resolution. |
| 428 | * @param samplesToAverage The number of samples to average from 1 to 127. |
| 429 | */ |
| 430 | void Counter::SetSamplesToAverage(int samplesToAverage) { |
| 431 | if (samplesToAverage < 1 || samplesToAverage > 127) { |
| 432 | wpi_setWPIErrorWithContext( |
| 433 | ParameterOutOfRange, |
| 434 | "Average counter values must be between 1 and 127"); |
| 435 | } |
| 436 | int32_t status = 0; |
| 437 | setCounterSamplesToAverage(m_counter, samplesToAverage, &status); |
| 438 | wpi_setErrorWithContext(status, getHALErrorMessage(status)); |
| 439 | } |
| 440 | |
| 441 | /** |
| 442 | * Read the current counter value. |
| 443 | * Read the value at this instant. It may still be running, so it reflects the |
| 444 | * current value. Next |
| 445 | * time it is read, it might have a different value. |
| 446 | */ |
| 447 | int32_t Counter::Get() const { |
| 448 | if (StatusIsFatal()) return 0; |
| 449 | int32_t status = 0; |
| 450 | int32_t value = getCounter(m_counter, &status); |
| 451 | wpi_setErrorWithContext(status, getHALErrorMessage(status)); |
| 452 | return value; |
| 453 | } |
| 454 | |
| 455 | /** |
| 456 | * Reset the Counter to zero. |
| 457 | * Set the counter value to zero. This doesn't effect the running state of the |
| 458 | * counter, just sets |
| 459 | * the current value to zero. |
| 460 | */ |
| 461 | void Counter::Reset() { |
| 462 | if (StatusIsFatal()) return; |
| 463 | int32_t status = 0; |
| 464 | resetCounter(m_counter, &status); |
| 465 | wpi_setErrorWithContext(status, getHALErrorMessage(status)); |
| 466 | } |
| 467 | |
| 468 | /** |
| 469 | * Get the Period of the most recent count. |
| 470 | * Returns the time interval of the most recent count. This can be used for |
| 471 | * velocity calculations |
| 472 | * to determine shaft speed. |
| 473 | * @returns The period between the last two pulses in units of seconds. |
| 474 | */ |
| 475 | double Counter::GetPeriod() const { |
| 476 | if (StatusIsFatal()) return 0.0; |
| 477 | int32_t status = 0; |
| 478 | double value = getCounterPeriod(m_counter, &status); |
| 479 | wpi_setErrorWithContext(status, getHALErrorMessage(status)); |
| 480 | return value; |
| 481 | } |
| 482 | |
| 483 | /** |
| 484 | * Set the maximum period where the device is still considered "moving". |
| 485 | * Sets the maximum period where the device is considered moving. This value is |
| 486 | * used to determine |
| 487 | * the "stopped" state of the counter using the GetStopped method. |
| 488 | * @param maxPeriod The maximum period where the counted device is considered |
| 489 | * moving in |
| 490 | * seconds. |
| 491 | */ |
| 492 | void Counter::SetMaxPeriod(double maxPeriod) { |
| 493 | if (StatusIsFatal()) return; |
| 494 | int32_t status = 0; |
| 495 | setCounterMaxPeriod(m_counter, maxPeriod, &status); |
| 496 | wpi_setErrorWithContext(status, getHALErrorMessage(status)); |
| 497 | } |
| 498 | |
| 499 | /** |
| 500 | * Select whether you want to continue updating the event timer output when |
| 501 | * there are no samples captured. |
| 502 | * The output of the event timer has a buffer of periods that are averaged and |
| 503 | * posted to |
| 504 | * a register on the FPGA. When the timer detects that the event source has |
| 505 | * stopped |
| 506 | * (based on the MaxPeriod) the buffer of samples to be averaged is emptied. If |
| 507 | * you |
| 508 | * enable the update when empty, you will be notified of the stopped source and |
| 509 | * the event |
| 510 | * time will report 0 samples. If you disable update when empty, the most |
| 511 | * recent average |
| 512 | * will remain on the output until a new sample is acquired. You will never see |
| 513 | * 0 samples |
| 514 | * output (except when there have been no events since an FPGA reset) and you |
| 515 | * will likely not |
| 516 | * see the stopped bit become true (since it is updated at the end of an average |
| 517 | * and there are |
| 518 | * no samples to average). |
| 519 | * @param enabled True to enable update when empty |
| 520 | */ |
| 521 | void Counter::SetUpdateWhenEmpty(bool enabled) { |
| 522 | if (StatusIsFatal()) return; |
| 523 | int32_t status = 0; |
| 524 | setCounterUpdateWhenEmpty(m_counter, enabled, &status); |
| 525 | wpi_setErrorWithContext(status, getHALErrorMessage(status)); |
| 526 | } |
| 527 | |
| 528 | /** |
| 529 | * Determine if the clock is stopped. |
| 530 | * Determine if the clocked input is stopped based on the MaxPeriod value set |
| 531 | * using the |
| 532 | * SetMaxPeriod method. If the clock exceeds the MaxPeriod, then the device (and |
| 533 | * counter) are |
| 534 | * assumed to be stopped and it returns true. |
| 535 | * @return Returns true if the most recent counter period exceeds the MaxPeriod |
| 536 | * value set by |
| 537 | * SetMaxPeriod. |
| 538 | */ |
| 539 | bool Counter::GetStopped() const { |
| 540 | if (StatusIsFatal()) return false; |
| 541 | int32_t status = 0; |
| 542 | bool value = getCounterStopped(m_counter, &status); |
| 543 | wpi_setErrorWithContext(status, getHALErrorMessage(status)); |
| 544 | return value; |
| 545 | } |
| 546 | |
| 547 | /** |
| 548 | * The last direction the counter value changed. |
| 549 | * @return The last direction the counter value changed. |
| 550 | */ |
| 551 | bool Counter::GetDirection() const { |
| 552 | if (StatusIsFatal()) return false; |
| 553 | int32_t status = 0; |
| 554 | bool value = getCounterDirection(m_counter, &status); |
| 555 | wpi_setErrorWithContext(status, getHALErrorMessage(status)); |
| 556 | return value; |
| 557 | } |
| 558 | |
| 559 | /** |
| 560 | * Set the Counter to return reversed sensing on the direction. |
| 561 | * This allows counters to change the direction they are counting in the case of |
| 562 | * 1X and 2X |
| 563 | * quadrature encoding only. Any other counter mode isn't supported. |
| 564 | * @param reverseDirection true if the value counted should be negated. |
| 565 | */ |
| 566 | void Counter::SetReverseDirection(bool reverseDirection) { |
| 567 | if (StatusIsFatal()) return; |
| 568 | int32_t status = 0; |
| 569 | setCounterReverseDirection(m_counter, reverseDirection, &status); |
| 570 | wpi_setErrorWithContext(status, getHALErrorMessage(status)); |
| 571 | } |
| 572 | |
| 573 | void Counter::UpdateTable() { |
| 574 | if (m_table != nullptr) { |
| 575 | m_table->PutNumber("Value", Get()); |
| 576 | } |
| 577 | } |
| 578 | |
| 579 | void Counter::StartLiveWindowMode() {} |
| 580 | |
| 581 | void Counter::StopLiveWindowMode() {} |
| 582 | |
| 583 | std::string Counter::GetSmartDashboardType() const { return "Counter"; } |
| 584 | |
| 585 | void Counter::InitTable(std::shared_ptr<ITable> subTable) { |
| 586 | m_table = subTable; |
| 587 | UpdateTable(); |
| 588 | } |
| 589 | |
| 590 | std::shared_ptr<ITable> Counter::GetTable() const { return m_table; } |