4 #ifdef ENABLE_TC_WAVEFORM_INTERRUPT 6 #endif // ENABLE_TC_WAVEFORM_INTERRUPT 8 #include "misc/debug_gpio.h" 16 #if (BOARD == SAME70_XPLAINED) 17 #define TIMER_PIN PIN_TC0_TIOA0 18 #elif (BOARD == USER_BOARD) 19 #define TIMER_PIN GPIO_8_PIN 21 #endif // TIMER_IO_DEBUG 31 static const uint32_t
g_divisors[5] = { 2, 8, 32, 128, 0 };
44 #endif // TIMER_IO_DEBUG 48 #ifdef ENABLE_TC_WAVEFORM_INTERRUPT 53 static inline void timer_report(
void)
62 if (g_times[k] > g_times[k-1])
64 sum += g_times[k] - g_times[k-1];
69 printf(
"avg=%u us expected=%u us\r\n",
71 (
unsigned int)(1000000.0/(TC_SAMPLE_SENSORS_RATE_HZ*1.0)));
73 printf(
"t0=%u t%d=%u diff=%u\r\n",
74 (
unsigned int)g_times[0],
75 TC_SAMPLE_SENSORS_RATE_HZ,
76 (
unsigned int)g_times[TC_SAMPLE_SENSORS_RATE_HZ],
82 static void timer_register_callback(
void (*func)(
void))
102 #endif // ENABLE_TC_WAVEFORM_INTERRUPT 140 #ifdef ENABLE_TC_WAVEFORM_INTERRUPT 141 timer_register_callback(func);
148 #endif // ENABLE_TC_WAVEFORM_INTERRUPT 151 printf(
"rc: %u, ra: %u\r\n", (
unsigned int)rc, (
unsigned int)ra);
152 printf(
"Start waveform: Frequency = %d Hz,Duty Cycle = %2d%%\n\r",
154 #endif // TIMER_DEBUG 162 #ifdef ENABLE_TC_CAPTURE_INTERRUPT 163 static uint32_t g_captured;
164 extern void gps_sync_int_handler(
int index,
int addTimeSinceTrigger);
182 g_led.gps_timeMs = g_gpsTimeOfWeekMs;
185 gps_sync_int_handler(0,1);
189 #endif // ENABLE_TC_CAPTURE_INTERRUPT 194 if (!g_capture_initialized)
197 #ifdef ENABLE_TC_CAPTURE_INTERRUPT 199 #endif // ENABLE_TC_CAPTURE_INTERRUPT 208 if (!g_capture_initialized)
211 #ifdef ENABLE_TC_CAPTURE_INTERRUPT 213 #endif // ENABLE_TC_CAPTURE_INTERRUPT 222 if (g_capture_initialized)
243 #ifdef ENABLE_TC_CAPTURE_INTERRUPT 250 #endif // ENABLE_TC_CAPTURE_INTERRUPT 254 g_capture_initialized = 1;
260 #ifdef ENABLE_TC_CAPTURE_INTERRUPT 265 #endif // ENABLE_TC_CAPTURE_INTERRUPT 324 #ifdef ENABLE_TC_WAVEFORM_INTERRUPT
static unsigned int g_wvf_channel
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.
static void timer_io_enable(void)
static void ioport_set_pin_level(ioport_pin_t pin, bool level)
Set an IOPORT pin to a specified logical value.
void pmc_enable_pck(uint32_t ul_id)
Enable the specified programmable clock.
#define TC0
(TC0 ) Base Address
#define TC_CMR_TCCLKS_TIMER_CLOCK2
(TC_CMR) Clock selected: internal MCK/8 clock signal (from PMC)
void tc_stop(Tc *p_tc, uint32_t ul_channel)
Stop the TC clock on the specified channel.
#define TC_CMR_TCCLKS_XC2
(TC_CMR) Clock selected: XC2
#define TC_CMR_ACPA_CLEAR
(TC_CMR) Clear
__STATIC_INLINE void NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority)
Set Interrupt Priority.
#define TC_SAMPLE_SENSORS_RATE_HZ
#define TC_IMR_CPCS
(TC_IMR) RC Compare
void tc_disable_interrupt(Tc *p_tc, uint32_t ul_channel, uint32_t ul_sources)
Disable TC interrupts on the specified channel.
static uint16_t g_rollover
#define TC_IER_LDRAS
(TC_IER) RA Loading
static const uint32_t g_divisors[5]
uint32_t tc_read_cv(Tc *p_tc, uint32_t ul_channel)
Read the counter value on the specified channel.
#define TC_CMR_ETRGEDG_RISING
(TC_CMR) Rising edge
#define TC_CMR_WAVE
(TC_CMR) Waveform Mode
void tc_start(Tc *p_tc, uint32_t ul_channel)
Start the TC clock on the specified channel.
void pmc_disable_pck(uint32_t ul_id)
Disable the specified programmable clock.
#define TC_CMR_ACPC_CLEAR
(TC_CMR) Clear
__STATIC_INLINE void NVIC_DisableIRQ(IRQn_Type IRQn)
Disable External Interrupt.
#define TC_CMR_ACPA_SET
(TC_CMR) Set
void timer_time_init(void)
#define TC_SAMPLE_SENSORS_ID
__STATIC_INLINE void NVIC_EnableIRQ(IRQn_Type IRQn)
Enable External Interrupt.
void tc_init(Tc *p_tc, uint32_t ul_channel, uint32_t ul_mode)
Configure TC for timer, waveform generation, or capture.
#define TC_CMR_WAVSEL_UP
(TC_CMR) UP mode without automatic trigger on RC Compare
static int g_capture_initialized
int timer_capture_disable(void)
#define TC_TIME_SYNC_CHANNEL
uint32_t tc_read_ra(Tc *p_tc, uint32_t ul_channel)
Read TC Register A (RA) on the specified channel.
#define TC_CMR_CPCTRG
(TC_CMR) RC Compare Trigger Enable
void TC_TIME_HANDLER(void)
#define TC_IER_CPCS
(TC_IER) RC Compare
static void(* g_wvf_callback)(void)
#define TC_CMR_LDRA_RISING
(TC_CMR) Rising edge of TIOA
volatile uint64_t time_cv(void)
#define PMC_PCK_PRES(value)
__STATIC_INLINE void NVIC_ClearPendingIRQ(IRQn_Type IRQn)
Clear Pending Interrupt.
#define TC_IDR_CPCS
(TC_IDR) RC Compare
#define TC_BMR_TC2XC2S_TIOA1
(TC_BMR) Signal connected to XC2: TIOA1
uint32_t tc_get_status(Tc *p_tc, uint32_t ul_channel)
Get the current status for the specified TC channel.
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.
#define TC_BMR_TC1XC1S_TIOA0
(TC_BMR) Signal connected to XC1: TIOA0
static void time_channel_init(uint32_t channel, uint32_t intclock)
uint32_t pmc_switch_pck_to_mck(uint32_t ul_id, uint32_t ul_pres)
Switch programmable clock source selection to mck.
int timer_capture_enable(void)
#define TC3
(TC3 ) Base Address
static void ioport_set_pin_dir(ioport_pin_t pin, enum ioport_direction dir)
Set direction for a single IOPORT pin.
#define TC_TIME_SYNC_IRQn
void tc_enable_interrupt(Tc *p_tc, uint32_t ul_channel, uint32_t ul_sources)
Enable the TC interrupts on the specified channel.
void timer_capture_init(void)
#define TC_TIME_SYNC_HANDLER
#define TC_SAMPLE_SENSORS_HANDLER
#define TIME_TICKS_PER_US
uint32_t timer_captured(void)
static void sysclk_enable_peripheral_clock(uint32_t ul_id)
Enable a peripheral's clock.
Autogenerated API include file for the Atmel Software Framework (ASF)
void timer_waveform_init(unsigned int channel, void(*func)(void))
#define TC_SAMPLE_SENSORS_CHANNEL
void tc_set_block_mode(Tc *p_tc, uint32_t ul_blockmode)
Configure the TC Block mode.
#define TC_CMR_ABETRG
(TC_CMR) TIOA or TIOB External Trigger Selection
#define TC_TIME_SYNC_IER_MASK
#define TC_CMR_ACPC_SET
(TC_CMR) Set
#define TC_SAMPLE_SENSORS_IRQn
static uint32_t sysclk_get_peripheral_bus_hz(const volatile void *module)
Retrieves the current rate in Hz of the Peripheral Bus clock attached to the specified peripheral...
#define TC_CMR_TCCLKS_XC1
(TC_CMR) Clock selected: XC1