32 #pragma GCC optimize ("O2") 51 #define NR_ADV_HANDLERS 8 53 #define NR_GEN_HANDLERS 7 55 #define NR_BAS_HANDLERS 1 79 .clk = RCC_APB2Periph_TIM1,
80 .handlers = tim1_handlers,
86 .state = &timer_state[0],
97 .clk = RCC_APB1Periph_TIM2,
98 .handlers = tim2_handlers,
104 .state = &timer_state[1],
116 .clk = RCC_APB1Periph_TIM3,
117 .handlers = tim3_handlers,
123 .state = &timer_state[2],
135 .clk = RCC_APB1Periph_TIM4,
136 .handlers = tim4_handlers,
142 .state = &timer_state[3],
154 .clk = RCC_APB1Periph_TIM5,
155 .handlers = tim5_handlers,
161 .state = &timer_state[4],
172 .clk = RCC_APB1Periph_TIM6,
173 .handlers = tim6_handlers,
179 .state = &timer_state[5],
184 .clk = RCC_APB1Periph_TIM7,
185 .handlers = tim7_handlers,
191 .state = &timer_state[6],
196 .clk = RCC_APB2Periph_TIM8,
197 .handlers = tim8_handlers,
203 .state = &timer_state[7],
216 .clk = RCC_APB2Periph_TIM9,
217 .handlers = tim9_handlers,
223 .state = &timer_state[8],
228 .clk = RCC_APB2Periph_TIM10,
229 .handlers = tim10_handlers,
235 .state = &timer_state[9],
240 .clk = RCC_APB2Periph_TIM11,
241 .handlers = tim11_handlers,
247 .state = &timer_state[10],
252 .clk = RCC_APB1Periph_TIM12,
253 .handlers = tim12_handlers,
259 .state = &timer_state[11],
264 .clk = RCC_APB1Periph_TIM13,
265 .handlers = tim13_handlers,
271 .state = &timer_state[12],
276 .clk = RCC_APB1Periph_TIM14,
277 .handlers = tim14_handlers,
283 .state = &timer_state[13],
306 RCC_APB2PeriphClockCmd(dev->
clk, ENABLE);
308 RCC_APB1PeriphClockCmd(dev->
clk, ENABLE);
321 RCC_APB2PeriphClockCmd(dev->
clk, ENABLE);
322 RCC_APB2PeriphResetCmd(dev->
clk, ENABLE);
323 RCC_APB2PeriphResetCmd(dev->
clk, DISABLE);
325 RCC_APB1PeriphClockCmd(dev->
clk, ENABLE);
326 RCC_APB1PeriphResetCmd(dev->
clk, ENABLE);
327 RCC_APB1PeriphResetCmd(dev->
clk, DISABLE);
347 (dev->
regs)->CCER = 0;
359 TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
360 TIM_TypeDef *tim = dev->
regs;
372 TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
374 TIM_TimeBaseStructure.TIM_Period = (period - 1) &
get_timer_mask(dev);
375 uint32_t freq = (uint32_t)khz * 1000;
379 if (tim == TIM1 || tim == TIM8 || tim == TIM9 || tim == TIM10 || tim == TIM11) {
385 prescaler = ((tf + freq/4) / freq) - 1;
387 TIM_TimeBaseStructure.TIM_Prescaler = prescaler;
388 freq = tf / prescaler;
392 TIM_TimeBaseStructure.TIM_ClockDivision = 0;
393 TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
394 TIM_TimeBaseInit(tim, &TIM_TimeBaseStructure);
629 uint32_t dsr = dev->
regs->DIER & dev->
regs->SR & irq_mask;
637 dev->
regs->SR &= ~dsr;
644 if (dier_sr & irq_mask) {
660 if(t>max_isr_time) max_isr_time=t;
672 if(t>max_isr_time) max_isr_time=t;
681 uint32_t dsr = dev->
regs->DIER & dev->
regs->SR;
690 dev->
regs->SR &= ~dsr;
695 if(t>max_isr_time) max_isr_time=t;
704 uint32_t dsr = dev->
regs->DIER & dev->
regs->SR;
711 dev->
regs->SR &= ~dsr;
716 if(t>max_isr_time) max_isr_time=t;
725 uint32_t dsr = dev->
regs->DIER & dev->
regs->SR;
735 dev->
regs->SR &= ~dsr;
740 if(t>max_isr_time) max_isr_time=t;
750 uint32_t dsr = dev->
regs->DIER & dev->
regs->SR;
757 dev->
regs->SR &= ~dsr;
762 if(t>max_isr_time) max_isr_time=t;
779 #define PRIO_DISABLE_FLAG 0x80 787 case 2: irq=TIM2_IRQn;
break;
788 case 3: irq=TIM3_IRQn;
break;
789 case 4: irq=TIM4_IRQn;
break;
790 case 5: irq=TIM5_IRQn;
break;
791 case 6: irq=TIM6_DAC_IRQn;
break;
792 case 7: irq=TIM7_IRQn;
break;
794 case 9: irq=TIM1_BRK_TIM9_IRQn;
break;
795 case 10: irq=TIM1_UP_TIM10_IRQn;
break;
796 case 11: irq=TIM1_TRG_COM_TIM11_IRQn;
break;
797 case 12: irq=TIM8_BRK_TIM12_IRQn;
break;
798 case 13: irq=TIM8_UP_TIM13_IRQn;
break;
799 case 14: irq=TIM8_TRG_COM_TIM14_IRQn;
break;
805 NVIC_DisableIRQ(irq);
813 uint8_t is_timer1 = (dev->
id == 1);
819 irq = is_timer1 ? TIM1_UP_TIM10_IRQn : TIM8_UP_TIM13_IRQn;
825 irq = is_timer1 ? TIM1_CC_IRQn : TIM8_CC_IRQn;
829 irq = is_timer1 ? TIM1_TRG_COM_TIM11_IRQn : TIM8_TRG_COM_TIM14_IRQn;
832 irq = is_timer1 ? TIM1_BRK_TIM9_IRQn : TIM8_BRK_TIM12_IRQn;
837 NVIC_DisableIRQ(irq);
840 NVIC_SetPriority(irq,priority);
static uint32_t stopwatch_getticks()
static void enable_irq(const timer_dev *dev, uint8_t interrupt, uint8_t priority)
static void timer_cc_enable(const timer_dev *dev, timer_Channel channel)
Enable a timer channel's capture/compare signal.
static void timer_cc_disable(const timer_dev *dev, timer_Channel channel)
Disable a timer channel's output compare or input capture signal.
void timer_set_mode(const timer_dev *dev, timer_Channel channel, timer_mode mode)
void TIM4_IRQHandler(void)
static void pwm_mode(const timer_dev *dev, uint8_t channel)
static void dispatch_adv_cc(const timer_dev *dev)
void timer_reset(const timer_dev *dev)
void TIM3_IRQHandler(void)
#define assert_param(expr)
void TIM8_CC_IRQHandler(void)
static INLINE uint32_t get_timer_mask(const timer_dev *dev)
void timer_enable_NVICirq(const timer_dev *dev, uint8_t interrupt, uint8_t priority)
static INLINE void timer_pause(const timer_dev *dev)
Stop a timer's counter from changing.
static void output_compare_mode(const timer_dev *dev, uint8_t channel)
void TIM1_TRG_COM_TIM11_IRQHandler(void)
static INLINE void timer_set_count(const timer_dev *dev, uint16_t value)
Sets the counter value for the given timer.
void timer_attach_interrupt(const timer_dev *dev, timer_interrupt_id interrupt, Handler handler, uint8_t priority)
Attach a timer interrupt.
#define TIMER_BDTR_LOCK_OFF
void TIM5_IRQHandler(void)
static INLINE void dispatch_single_irq(const timer_dev *dev, timer_interrupt_id iid, uint32_t irq_mask)
timer_interrupt_id
Timer interrupt number.
static AP_HAL::OwnPtr< AP_HAL::Device > dev
void TIM2_IRQHandler(void)
void timer_detach_interrupt(const timer_dev *dev, timer_interrupt_id interrupt)
Detach a timer interrupt.
static void dispatch_adv_up(const timer_dev *dev)
static Handler tim1_handlers [NR_ADV_HANDLERS] IN_CCM
void TIM1_BRK_TIM9_IRQHandler(void)
void enable_nvic_irq(uint8_t irq, uint8_t prio)
#define PRIO_DISABLE_FLAG
static void dispatch_adv_trg_com(const timer_dev *dev)
void TIM6_DAC_IRQHandler(void)
void timer_attach_all_interrupts(const timer_dev *dev, Handler handler)
static void dispatch_basic(const timer_dev *dev)
static void timer_oc_set_mode(const timer_dev *dev, timer_Channel _channel, timer_oc_mode mode, uint8_t flags)
Configure a channel's output compare mode.
void TIM8_BRK_TIM12_IRQHandler(void)
static void dispatch_general_h(const timer_dev *dev)
void timer_init(const timer_dev *dev)
static void timer_enable_irq(const timer_dev *dev, timer_interrupt_id interrupt)
Enable a timer interrupt.
static void timer_disable_irq(const timer_dev *dev, timer_interrupt_id interrupt)
Disable a timer interrupt.
void TIM1_UP_TIM10_IRQHandler(void)
static void dispatch_adv_brk(const timer_dev *dev)
void TIM7_IRQHandler(void)
static void disable_channel(const timer_dev *dev, uint8_t channel)
void TIM8_TRG_COM_TIM14_IRQHandler(void)
uint32_t configTimeBase(const timer_dev *dev, uint16_t period, uint16_t khz)
void TIM8_UP_TIM13_IRQHandler(void)
void timer_disable_NVICirq(const timer_dev *dev, uint8_t interrupt)
static INLINE void handle_irq(const timer_dev *dev, uint32_t dier_sr, uint32_t irq_mask, uint32_t iid)
static void dispatch_general(const timer_dev *dev)
static void enable_advanced_irq(const timer_dev *dev, timer_interrupt_id id, uint8_t priority)
void TIM1_CC_IRQHandler(void)
void revo_call_handler(Handler h, uint32_t arg)
void timer_foreach(void(*fn)(const timer_dev *))
Call a function on timer devices.
void timer_disable(const timer_dev *dev)
Disable a timer.