Counter Class Reference
#include <Counter.h>


Public Types | |
| enum | Mode { kTwoPulse = 0, kSemiperiod = 1, kPulseLength = 2, kExternalDirection = 3 } |
Public Member Functions | |
| Counter () | |
| Counter (UINT32 channel) | |
| Counter (UINT8 moduleNumber, UINT32 channel) | |
| Counter (DigitalSource *source) | |
| Counter (DigitalSource &source) | |
| Counter (AnalogTrigger *trigger) | |
| Counter (AnalogTrigger &trigger) | |
| Counter (EncodingType encodingType, DigitalSource *upSource, DigitalSource *downSource, bool inverted) | |
| virtual | ~Counter () |
| void | SetUpSource (UINT32 channel) |
| void | SetUpSource (UINT8 moduleNumber, UINT32 channel) |
| void | SetUpSource (AnalogTrigger *analogTrigger, AnalogTriggerOutput::Type triggerType) |
| void | SetUpSource (AnalogTrigger &analogTrigger, AnalogTriggerOutput::Type triggerType) |
| void | SetUpSource (DigitalSource *source) |
| void | SetUpSource (DigitalSource &source) |
| void | SetUpSourceEdge (bool risingEdge, bool fallingEdge) |
| void | ClearUpSource () |
| void | SetDownSource (UINT32 channel) |
| void | SetDownSource (UINT8 moduleNumber, UINT32 channel) |
| void | SetDownSource (AnalogTrigger *analogTrigger, AnalogTriggerOutput::Type triggerType) |
| void | SetDownSource (AnalogTrigger &analogTrigger, AnalogTriggerOutput::Type triggerType) |
| void | SetDownSource (DigitalSource *source) |
| void | SetDownSource (DigitalSource &source) |
| void | SetDownSourceEdge (bool risingEdge, bool fallingEdge) |
| void | ClearDownSource () |
| void | SetUpDownCounterMode () |
| void | SetExternalDirectionMode () |
| void | SetSemiPeriodMode (bool highSemiPeriod) |
| void | SetPulseLengthMode (float threshold) |
| void | SetReverseDirection (bool reverseDirection) |
| void | Start () |
| INT32 | Get () |
| void | Reset () |
| void | Stop () |
| double | GetPeriod () |
| void | SetMaxPeriod (double maxPeriod) |
| void | SetUpdateWhenEmpty (bool enabled) |
| bool | GetStopped () |
| bool | GetDirection () |
Detailed Description
Class for counting the number of ticks on a digital input channel. This is a general purpose class for counting repetitive events. It can return the number of counts, the period of the most recent cycle, and detect when the signal being counted has stopped by supplying a maximum cycle time.
Definition at line 20 of file Counter.h.
Constructor & Destructor Documentation
| Counter::Counter | ( | ) |
Create an instance of a counter where no sources are selected. Then they all must be selected by calling functions to specify the upsource and the downsource independently.
Definition at line 45 of file Counter.cpp.
| Counter::Counter | ( | UINT32 | channel | ) | [explicit] |
Create an instance of a Counter object. Create an up-Counter instance given a channel. The default digital module is assumed.
Definition at line 82 of file Counter.cpp.
| Counter::Counter | ( | UINT8 | moduleNumber, | |
| UINT32 | channel | |||
| ) |
Create an instance of a Counter object. Create an instance of an up-Counter given a digital module and a channel.
- Parameters:
-
moduleNumber The digital module (1 or 2). channel The channel in the digital module
Definition at line 98 of file Counter.cpp.
| Counter::Counter | ( | DigitalSource * | source | ) | [explicit] |
Create an instance of a counter from a Digital Input. This is used if an existing digital input is to be shared by multiple other objects such as encoders.
Definition at line 58 of file Counter.cpp.
| Counter::Counter | ( | AnalogTrigger * | trigger | ) | [explicit] |
Create an instance of a Counter object. Create an instance of a simple up-Counter given an analog trigger. Use the trigger state output from the analog trigger.
Definition at line 113 of file Counter.cpp.
| Counter::~Counter | ( | ) | [virtual] |
Delete the Counter object.
Definition at line 168 of file Counter.cpp.
Member Function Documentation
| void Counter::ClearDownSource | ( | ) |
Disable the down counting source to the counter.
Definition at line 429 of file Counter.cpp.
| void Counter::ClearUpSource | ( | ) |
Disable the up counting source to the counter.
Definition at line 296 of file Counter.cpp.
| INT32 Counter::Get | ( | ) | [virtual] |
Read the current counter value. Read the value at this instant. It may still be running, so it reflects the current value. Next time it is read, it might have a different value.
Implements CounterBase.
Definition at line 521 of file Counter.cpp.
| bool Counter::GetDirection | ( | ) | [virtual] |
The last direction the counter value changed.
- Returns:
- The last direction the counter value changed.
Implements CounterBase.
Definition at line 637 of file Counter.cpp.
| bool Counter::GetStopped | ( | ) | [virtual] |
Determine if the clock is stopped. Determine if the clocked input is stopped based on the MaxPeriod value set using the SetMaxPeriod method. If the clock exceeds the MaxPeriod, then the device (and counter) are assumed to be stopped and it returns true.
- Returns:
- Returns true if the most recent counter period exceeds the MaxPeriod value set by SetMaxPeriod.
Implements CounterBase.
Definition at line 625 of file Counter.cpp.
| void Counter::Reset | ( | ) | [virtual] |
Reset the Counter to zero. Set the counter value to zero. This doesn't effect the running state of the counter, just sets the current value to zero.
Implements CounterBase.
Definition at line 535 of file Counter.cpp.
| void Counter::SetDownSource | ( | UINT32 | channel | ) |
Set the down counting source to be a digital input channel. The slot will be set to the default digital module slot.
Definition at line 321 of file Counter.cpp.
| void Counter::SetDownSource | ( | UINT8 | moduleNumber, | |
| UINT32 | channel | |||
| ) |
Set the down counting source to be a digital input slot and channel.
- Parameters:
-
moduleNumber The digital module (1 or 2). channel The digital channel (1..14).
Definition at line 334 of file Counter.cpp.
| void Counter::SetDownSource | ( | AnalogTrigger * | analogTrigger, | |
| AnalogTriggerOutput::Type | triggerType | |||
| ) |
Set the down counting source to be an analog trigger.
- Parameters:
-
analogTrigger The analog trigger object that is used for the Down Source triggerType The analog trigger output that will trigger the counter.
Definition at line 346 of file Counter.cpp.
| void Counter::SetDownSource | ( | DigitalSource * | source | ) |
Set the source object that causes the counter to count down. Set the down counting DigitalSource.
Definition at line 367 of file Counter.cpp.
| void Counter::SetDownSource | ( | AnalogTrigger & | analogTrigger, | |
| AnalogTriggerOutput::Type | triggerType | |||
| ) |
Set the down counting source to be an analog trigger.
- Parameters:
-
analogTrigger The analog trigger object that is used for the Down Source triggerType The analog trigger output that will trigger the counter.
Definition at line 358 of file Counter.cpp.
| void Counter::SetDownSource | ( | DigitalSource & | source | ) |
Set the source object that causes the counter to count down. Set the down counting DigitalSource.
Definition at line 404 of file Counter.cpp.
| void Counter::SetDownSourceEdge | ( | bool | risingEdge, | |
| bool | fallingEdge | |||
| ) |
Set the edge sensitivity on a down counting source. Set the down source to either detect rising edges or falling edges.
Definition at line 413 of file Counter.cpp.
| void Counter::SetExternalDirectionMode | ( | ) |
Set external direction mode on this counter. Counts are sourced on the Up counter input. The Down counter input represents the direction to count.
Definition at line 467 of file Counter.cpp.
| void Counter::SetMaxPeriod | ( | double | maxPeriod | ) | [virtual] |
Set the maximum period where the device is still considered "moving". Sets the maximum period where the device is considered moving. This value is used to determine the "stopped" state of the counter using the GetStopped method.
- Parameters:
-
maxPeriod The maximum period where the counted device is considered moving in seconds.
Implements CounterBase.
Definition at line 589 of file Counter.cpp.
| void Counter::SetPulseLengthMode | ( | float | threshold | ) |
Configure the counter to count in up or down based on the length of the input pulse. This mode is most useful for direction sensitive gear tooth sensors.
- Parameters:
-
threshold The pulse length beyond which the counter counts the opposite direction. Units are seconds.
Definition at line 494 of file Counter.cpp.
| void Counter::SetReverseDirection | ( | bool | reverseDirection | ) |
Set the Counter to return reversed sensing on the direction. This allows counters to change the direction they are counting in the case of 1X and 2X quadrature encoding only. Any other counter mode isn't supported.
- Parameters:
-
reverseDirection true if the value counted should be negated.
Definition at line 652 of file Counter.cpp.
| void Counter::SetSemiPeriodMode | ( | bool | highSemiPeriod | ) |
Set Semi-period mode on this counter. Counts up on both rising and falling edges.
Definition at line 479 of file Counter.cpp.
| void Counter::SetUpdateWhenEmpty | ( | bool | enabled | ) |
Select whether you want to continue updating the event timer output when there are no samples captured. The output of the event timer has a buffer of periods that are averaged and posted to a register on the FPGA. When the timer detects that the event source has stopped (based on the MaxPeriod) the buffer of samples to be averaged is emptied. If you enable the update when empty, you will be notified of the stopped source and the event time will report 0 samples. If you disable update when empty, the most recent average will remain on the output until a new sample is acquired. You will never see 0 samples output (except when there have been no events since an FPGA reset) and you will likely not see the stopped bit become true (since it is updated at the end of an average and there are no samples to average).
Definition at line 609 of file Counter.cpp.
| void Counter::SetUpDownCounterMode | ( | ) |
Set standard up / down counting mode on this counter. Up and down counts are sourced independently from two inputs.
Definition at line 454 of file Counter.cpp.
| void Counter::SetUpSource | ( | DigitalSource & | source | ) |
Set the source object that causes the counter to count up. Set the up counting DigitalSource.
Definition at line 271 of file Counter.cpp.
| void Counter::SetUpSource | ( | DigitalSource * | source | ) |
Set the source object that causes the counter to count up. Set the up counting DigitalSource.
Definition at line 236 of file Counter.cpp.
| void Counter::SetUpSource | ( | UINT8 | moduleNumber, | |
| UINT32 | channel | |||
| ) |
Set the up source for the counter as digital input channel and slot.
- Parameters:
-
moduleNumber The digital module (1 or 2). channel The digital channel (1..14).
Definition at line 192 of file Counter.cpp.
| void Counter::SetUpSource | ( | AnalogTrigger & | analogTrigger, | |
| AnalogTriggerOutput::Type | triggerType | |||
| ) |
Set the up counting source to be an analog trigger.
- Parameters:
-
analogTrigger The analog trigger object that is used for the Up Source triggerType The analog trigger output that will trigger the counter.
Definition at line 227 of file Counter.cpp.
| void Counter::SetUpSource | ( | UINT32 | channel | ) |
Set the upsource for the counter as a digital input channel. The slot will be the default digital module slot.
Definition at line 203 of file Counter.cpp.
| void Counter::SetUpSource | ( | AnalogTrigger * | analogTrigger, | |
| AnalogTriggerOutput::Type | triggerType | |||
| ) |
Set the up counting source to be an analog trigger.
- Parameters:
-
analogTrigger The analog trigger object that is used for the Up Source triggerType The analog trigger output that will trigger the counter.
Definition at line 215 of file Counter.cpp.
| void Counter::SetUpSourceEdge | ( | bool | risingEdge, | |
| bool | fallingEdge | |||
| ) |
Set the edge sensitivity on an up counting source. Set the up source to either detect rising edges or falling edges.
Definition at line 280 of file Counter.cpp.
| void Counter::Start | ( | ) | [virtual] |
Start the Counter counting. This enables the counter and it starts accumulating counts from the associated input channel. The counter value is not reset on starting, and still has the previous value.
Implements CounterBase.
Definition at line 508 of file Counter.cpp.
| void Counter::Stop | ( | ) | [virtual] |
Stop the Counter. Stops the counting but doesn't effect the current value.
Implements CounterBase.
Definition at line 547 of file Counter.cpp.
The documentation for this class was generated from the following files:
Generated on Thu Jan 12 2012 22:35:29 for WPILibC++ by
1.7.1