|
void | tc_disable_interrupt (Tc *p_tc, uint32_t ul_channel, uint32_t ul_sources) |
| Disable TC interrupts on the specified channel. More...
|
|
void | tc_disable_qdec_interrupt (Tc *p_tc, uint32_t ul_sources) |
| Disable TC QDEC interrupts. More...
|
|
void | tc_enable_interrupt (Tc *p_tc, uint32_t ul_channel, uint32_t ul_sources) |
| Enable the TC interrupts on the specified channel. More...
|
|
void | tc_enable_qdec_interrupt (Tc *p_tc, uint32_t ul_sources) |
| Enable TC QDEC interrupts. More...
|
|
uint32_t | tc_find_mck_divisor (uint32_t ul_freq, uint32_t ul_mck, uint32_t *p_uldiv, uint32_t *ul_tcclks, uint32_t ul_boardmck) |
| Find the best MCK divisor. More...
|
|
uint32_t | tc_get_interrupt_mask (Tc *p_tc, uint32_t ul_channel) |
| Read the TC interrupt mask for the specified channel. More...
|
|
uint32_t | tc_get_qdec_interrupt_mask (Tc *p_tc) |
| Read TC QDEC interrupt mask. More...
|
|
uint32_t | tc_get_qdec_interrupt_status (Tc *p_tc) |
| Get current TC QDEC interrupt status. More...
|
|
uint32_t | tc_get_status (Tc *p_tc, uint32_t ul_channel) |
| Get the current status for the specified TC channel. More...
|
|
void | tc_init (Tc *p_tc, uint32_t ul_Channel, uint32_t ul_Mode) |
| Configure TC for timer, waveform generation, or capture. More...
|
|
uint32_t | tc_init_2bit_gray (Tc *p_tc, uint32_t ul_channel, uint32_t ul_steppermode) |
| Configure TC for 2-bit Gray Counter for Stepper Motor. More...
|
|
uint32_t | tc_read_cv (Tc *p_tc, uint32_t ul_channel) |
| Read the counter value on the specified channel. More...
|
|
uint32_t | tc_read_ra (Tc *p_tc, uint32_t ul_channel) |
| Read TC Register A (RA) on the specified channel. More...
|
|
uint32_t | tc_read_rb (Tc *p_tc, uint32_t ul_channel) |
| Read TC Register B (RB) on the specified channel. More...
|
|
uint32_t | tc_read_rc (Tc *p_tc, uint32_t ul_channel) |
| Read TC Register C (RC) on the specified channel. More...
|
|
void | tc_set_block_mode (Tc *p_tc, uint32_t ul_blockmode) |
| Configure the TC Block mode. More...
|
|
void | tc_set_writeprotect (Tc *p_tc, uint32_t ul_enable) |
| Enable or disable write protection of TC registers. More...
|
|
void | tc_start (Tc *p_tc, uint32_t ul_channel) |
| Start the TC clock on the specified channel. More...
|
|
void | tc_stop (Tc *p_tc, uint32_t ul_channel) |
| Stop the TC clock on the specified channel. More...
|
|
void | tc_sync_trigger (Tc *p_tc) |
| Asserts a SYNC signal to generate a software trigger on all channels. More...
|
|
void | tc_write_ra (Tc *p_tc, uint32_t ul_channel, uint32_t ul_value) |
| Write to TC Register A (RA) on the specified channel. More...
|
|
void | tc_write_rb (Tc *p_tc, uint32_t ul_channel, uint32_t ul_value) |
| Write to TC Register B (RB) on the specified channel. More...
|
|
void | tc_write_rc (Tc *p_tc, uint32_t ul_channel, uint32_t ul_value) |
| Write to TC Register C (RC) on the selected channel. More...
|
|
This driver for Atmel® | SMART ARM®-based microcontrollers provides an interface for the configuration and management of the device's Timer Counter functionality.
The Timer Counter (TC) includes several identical 16-bit or 32-bit Timer Counter channels. Each channel can be independently programmed to perform a wide range of functions that includes frequency measurement, event counting, interval measurement, pulse generation, delay timing, and pulse width modulation.
Devices from the following series can use this module:
- Atmel | SMART SAM3
- Atmel | SMART SAM4S
- Atmel | SMART SAM4L
- Atmel | SMART SAM4E
- Atmel | SMART SAM4N
- Atmel | SMART SAM4CM
- Atmel | SMART SAM4C
- Atmel | SMART SAMG
The outline of this documentation is as follows:
Prerequisites
There are no prerequisites for this module.
Module Overview
The Timer Counter (TC) includes several identical 16-bit or 32-bit Timer Counter channels. The number of TC channels is device specific, refer to the device-specific datasheet for more information.
Each channel can be independently programmed to perform a wide range of functions that includes frequency measurement, event counting, interval measurement, pulse generation, delay timing, and pulse width modulation.
Each channel has three external clock inputs, five internal clock inputs, and two multi-purpose input/output signals which can be configured by the user. Each channel drives an internal interrupt signal which can be programmed to generate processor interrupts.
The Timer Counter (TC) embeds a quadrature decoder logic connected in front of the timers. When enabled, the quadrature decoder performs the input line filtering, decoding of quadrature signals and connects to the timers/counters in order to read the position and speed of the motor.
Special Considerations
External Clock
In all cases, if an external clock is used, the duration of each of its levels must be longer than the master clock (MCLK) period. The external clock frequency must be at least 2.5 times lower than the master clock.
External Trigger
If an external trigger is used, the duration of its pulses must be longer than the master clock (MCLK) period in order to be detected.
Extra Information
For extra information, see Extra Information for Timer Counter Driver. This includes:
Examples
For a list of examples related to this driver, see Examples for Timer Counter.
API Overview
◆ tc_disable_interrupt()
void tc_disable_interrupt |
( |
Tc * |
p_tc, |
|
|
uint32_t |
ul_channel, |
|
|
uint32_t |
ul_sources |
|
) |
| |
Disable TC interrupts on the specified channel.
- Parameters
-
[in,out] | p_tc | Module hardware register base address pointer |
[in] | ul_channel | Channel to configure |
[in] | ul_sources | A bitmask of Interrupt sources |
Where the input parameter ul_sources can be one or more of the following:
Parameter Value | Description |
TC_IDR_COVFS | Disables the Counter Overflow Interrupt |
TC_IDR_LOVRS | Disables the Load Overrun Interrupt |
TC_IDR_CPAS | Disables the RA Compare Interrupt |
TC_IDR_CPBS | Disables the RB Compare Interrupt |
TC_IDR_CPCS | Disables the RC Compare Interrupt |
TC_IDR_LDRAS | Disables the RA Load Interrupt |
TC_IDR_LDRBS | Disables the RB Load Interrupt |
TC_IDR_ETRGS | Disables the External Trigger Interrupt |
Definition at line 400 of file tc.c.
◆ tc_disable_qdec_interrupt()
void tc_disable_qdec_interrupt |
( |
Tc * |
p_tc, |
|
|
uint32_t |
ul_sources |
|
) |
| |
Disable TC QDEC interrupts.
- Note
- This function is not available on SAM4L or SAMG devices.
- Parameters
-
[out] | p_tc | Module hardware register base address pointer |
[in] | ul_sources | A bitmask of QDEC interrupts to be disabled |
Where the input parameter ul_sources can be one or more of the following:
Parameter Value | Description |
TC_QIDR_IDX | Disable the rising edge detected on IDX input interrupt |
TC_QIDR_DIRCHG | Disable the change in rotation direction detected interrupt |
TC_QIDR_QERR | Disable the quadrature error detected on PHA/PHB interrupt |
Definition at line 646 of file tc.c.
◆ tc_enable_interrupt()
void tc_enable_interrupt |
( |
Tc * |
p_tc, |
|
|
uint32_t |
ul_channel, |
|
|
uint32_t |
ul_sources |
|
) |
| |
Enable the TC interrupts on the specified channel.
- Parameters
-
[in,out] | p_tc | Module hardware register base address pointer |
[in] | ul_channel | Channel to configure |
[in] | ul_sources | Bitmask of interrupt sources |
Where the input parameter ul_sources can be one or more of the following:
Parameter Value | Description |
TC_IER_COVFS | Enables the Counter Overflow Interrupt |
TC_IER_LOVRS | Enables the Load Overrun Interrupt |
TC_IER_CPAS | Enables the RA Compare Interrupt |
TC_IER_CPBS | Enables the RB Compare Interrupt |
TC_IER_CPCS | Enables the RC Compare Interrupt |
TC_IER_LDRAS | Enables the RA Load Interrupt |
TC_IER_LDRBS | Enables the RB Load Interrupt |
TC_IER_ETRGS | Enables the External Trigger Interrupt |
Definition at line 362 of file tc.c.
◆ tc_enable_qdec_interrupt()
void tc_enable_qdec_interrupt |
( |
Tc * |
p_tc, |
|
|
uint32_t |
ul_sources |
|
) |
| |
Enable TC QDEC interrupts.
- Note
- This function is not available on SAM4L or SAMG devices.
- Parameters
-
[out] | p_tc | Module hardware register base address pointer |
[in] | ul_sources | A bitmask of QDEC interrupts to be enabled |
Where the input parameter ul_sources can be one or more of the following:
Parameter Value | Description |
TC_QIER_IDX | Enable the rising edge detected on IDX input interrupt |
TC_QIER_DIRCHG | Enable the change in rotation direction detected interrupt |
TC_QIER_QERR | Enable the quadrature error detected on PHA/PHB interrupt |
Definition at line 617 of file tc.c.
◆ tc_find_mck_divisor()
uint32_t tc_find_mck_divisor |
( |
uint32_t |
ul_freq, |
|
|
uint32_t |
ul_mck, |
|
|
uint32_t * |
p_uldiv, |
|
|
uint32_t * |
p_ultcclks, |
|
|
uint32_t |
ul_boardmck |
|
) |
| |
Find the best MCK divisor.
Finds the best MCK divisor given the timer frequency and MCK. The result is guaranteed to satisfy the following equation:
(MCK / (DIV * 65536)) <= freq <= (MCK / DIV)
With DIV being the lowest possible value, to maximize timing adjust resolution.
- Parameters
-
[in] | ul_freq | Desired timer frequency |
[in] | ul_mck | Master clock frequency |
[out] | p_uldiv | Divisor value |
[out] | p_ultcclks | TCCLKS field value for divisor |
[in] | ul_boardmck | Board clock frequency |
- Returns
- The divisor found status.
- Return values
-
0 | No suitable divisor was found |
1 | A divisor was found |
Definition at line 487 of file tc.c.
◆ tc_get_interrupt_mask()
uint32_t tc_get_interrupt_mask |
( |
Tc * |
p_tc, |
|
|
uint32_t |
ul_channel |
|
) |
| |
Read the TC interrupt mask for the specified channel.
- Parameters
-
[in] | p_tc | Module hardware register base address pointer |
[in] | ul_channel | Channel to read |
- Returns
- The TC interrupt mask value.
Definition at line 423 of file tc.c.
◆ tc_get_qdec_interrupt_mask()
uint32_t tc_get_qdec_interrupt_mask |
( |
Tc * |
p_tc | ) |
|
Read TC QDEC interrupt mask.
- Note
- This function is not available on SAM4L or SAMG devices.
- Parameters
-
[in] | p_tc | Module hardware register base address pointer |
- Returns
- The QDEC interrupt mask value.
Definition at line 665 of file tc.c.
◆ tc_get_qdec_interrupt_status()
uint32_t tc_get_qdec_interrupt_status |
( |
Tc * |
p_tc | ) |
|
Get current TC QDEC interrupt status.
- Note
- This function is not available on SAM4L or SAMG devices.
- Parameters
-
[in] | p_tc | Module hardware register base address pointer |
- Returns
- The TC QDEC interrupt status.
Definition at line 683 of file tc.c.
◆ tc_get_status()
uint32_t tc_get_status |
( |
Tc * |
p_tc, |
|
|
uint32_t |
ul_channel |
|
) |
| |
Get the current status for the specified TC channel.
- Parameters
-
[in] | p_tc | Module hardware register base address pointer |
[in] | ul_channel | Channel number |
- Returns
- The current TC status.
Definition at line 445 of file tc.c.
◆ tc_init()
void tc_init |
( |
Tc * |
p_tc, |
|
|
uint32_t |
ul_channel, |
|
|
uint32_t |
ul_mode |
|
) |
| |
Configure TC for timer, waveform generation, or capture.
- Parameters
-
[in,out] | p_tc | Module hardware register base address pointer |
[in] | ul_channel | Channel to configure |
[in] | ul_mode | Control mode register bitmask value to set |
- Note
- For more information regarding ul_mode configuration refer to the section entitled "Channel Mode Register: Capture Mode" and/or section "Waveform Operating Mode" in the device-specific datasheet.
-
If the TC is configured for waveform generation then the external event selection (EEVT) should only be set to TC_CMR_EEVT_TIOB, or the equivalent value of 0, if it really is the intention to use TIOB as an external event trigger. This is because this setting forces TIOB to be an input, even if the external event trigger has not been enabled with TC_CMR_ENETRG, and thus prevents normal operation of TIOB.
Definition at line 70 of file tc.c.
◆ tc_init_2bit_gray()
uint32_t tc_init_2bit_gray |
( |
Tc * |
p_tc, |
|
|
uint32_t |
ul_channel, |
|
|
uint32_t |
ul_steppermode |
|
) |
| |
Configure TC for 2-bit Gray Counter for Stepper Motor.
- Note
- The function tc_init() must be called prior to this one.
-
This function is not available on SAM3U devices.
- Parameters
-
[out] | p_tc | Module hardware register base address pointer |
[in] | ul_channel | Channel to configure |
[in] | ul_steppermode | Stepper motor mode register value to set |
- Returns
- 0 for OK.
Definition at line 147 of file tc.c.
◆ tc_read_cv()
uint32_t tc_read_cv |
( |
Tc * |
p_tc, |
|
|
uint32_t |
ul_channel |
|
) |
| |
Read the counter value on the specified channel.
- Parameters
-
[in] | p_tc | Module hardware register base address pointer |
[in] | ul_channel | Channel to read |
- Returns
- The counter value.
Definition at line 207 of file tc.c.
◆ tc_read_ra()
uint32_t tc_read_ra |
( |
Tc * |
p_tc, |
|
|
uint32_t |
ul_channel |
|
) |
| |
Read TC Register A (RA) on the specified channel.
- Parameters
-
[in] | p_tc | Module hardware register base address pointer |
[in] | ul_channel | Channel to read |
- Returns
- The TC Register A (RA) value.
Definition at line 227 of file tc.c.
◆ tc_read_rb()
uint32_t tc_read_rb |
( |
Tc * |
p_tc, |
|
|
uint32_t |
ul_channel |
|
) |
| |
Read TC Register B (RB) on the specified channel.
- Parameters
-
[in] | p_tc | Module hardware register base address pointer |
[in] | ul_channel | Channel to read |
- Returns
- The TC Register B (RB) value.
Definition at line 247 of file tc.c.
◆ tc_read_rc()
uint32_t tc_read_rc |
( |
Tc * |
p_tc, |
|
|
uint32_t |
ul_channel |
|
) |
| |
Read TC Register C (RC) on the specified channel.
- Parameters
-
[in] | p_tc | Module hardware register base address pointer |
[in] | ul_channel | Channel to read |
- Returns
- The Register C (RC) value.
Definition at line 267 of file tc.c.
◆ tc_set_block_mode()
void tc_set_block_mode |
( |
Tc * |
p_tc, |
|
|
uint32_t |
ul_blockmode |
|
) |
| |
Configure the TC Block mode.
- Note
- The function tc_init() must be called prior to this one.
- Parameters
-
[out] | p_tc | Module hardware register base address pointer |
[in] | ul_blockmode | Block mode register value to set |
- Note
- For more information regarding ul_blockmode configuration refer to the section entitled "TC Block Mode Register" in the device-specific datasheet.
Definition at line 123 of file tc.c.
◆ tc_set_writeprotect()
void tc_set_writeprotect |
( |
Tc * |
p_tc, |
|
|
uint32_t |
ul_enable |
|
) |
| |
Enable or disable write protection of TC registers.
- Note
- This function is not available on SAM3U devices.
- Parameters
-
[out] | p_tc | Module hardware register base address pointer |
[in] | ul_enable | 1 to enable, 0 to disable |
Definition at line 704 of file tc.c.
◆ tc_start()
void tc_start |
( |
Tc * |
p_tc, |
|
|
uint32_t |
ul_channel |
|
) |
| |
Start the TC clock on the specified channel.
- Parameters
-
[out] | p_tc | Module hardware register base address pointer |
[in] | ul_channel | Channel to configure |
Definition at line 169 of file tc.c.
◆ tc_stop()
void tc_stop |
( |
Tc * |
p_tc, |
|
|
uint32_t |
ul_channel |
|
) |
| |
Stop the TC clock on the specified channel.
- Parameters
-
[out] | p_tc | Module hardware register base address pointer |
[in] | ul_channel | Channel to configure |
Definition at line 187 of file tc.c.
◆ tc_sync_trigger()
void tc_sync_trigger |
( |
Tc * |
p_tc | ) |
|
Asserts a SYNC signal to generate a software trigger on all channels.
- Parameters
-
[out] | p_tc | Module hardware register base address pointer |
Definition at line 103 of file tc.c.
◆ tc_write_ra()
void tc_write_ra |
( |
Tc * |
p_tc, |
|
|
uint32_t |
ul_channel, |
|
|
uint32_t |
ul_value |
|
) |
| |
Write to TC Register A (RA) on the specified channel.
- Parameters
-
[out] | p_tc | Module hardware register base address pointer |
[in] | ul_channel | Channel to write |
[in] | ul_value | Value to write |
Definition at line 286 of file tc.c.
◆ tc_write_rb()
void tc_write_rb |
( |
Tc * |
p_tc, |
|
|
uint32_t |
ul_channel, |
|
|
uint32_t |
ul_value |
|
) |
| |
Write to TC Register B (RB) on the specified channel.
- Parameters
-
[out] | p_tc | Module hardware register base address pointer |
[in] | ul_channel | Channel to write |
[in] | ul_value | Value to write |
Definition at line 306 of file tc.c.
◆ tc_write_rc()
void tc_write_rc |
( |
Tc * |
p_tc, |
|
|
uint32_t |
ul_channel, |
|
|
uint32_t |
ul_value |
|
) |
| |
Write to TC Register C (RC) on the selected channel.
- Parameters
-
[out] | p_tc | Module hardware register base address pointer |
[in] | ul_channel | Channel to write |
[in] | ul_value | Value to write |
Definition at line 326 of file tc.c.